commit
62612580ef
3
.gitignore
vendored
3
.gitignore
vendored
|
@ -15,3 +15,6 @@ applet/
|
||||||
*.bak
|
*.bak
|
||||||
*.DS_Store
|
*.DS_Store
|
||||||
*.idea
|
*.idea
|
||||||
|
*.s
|
||||||
|
*.i
|
||||||
|
*.ii
|
||||||
|
|
332
.travis.yml
332
.travis.yml
|
@ -1,12 +1,13 @@
|
||||||
---
|
---
|
||||||
language: c
|
language: c
|
||||||
|
#
|
||||||
before_install:
|
before_install:
|
||||||
# Travis runs a detached head. We need to find the current branch
|
# Travis runs a detached head. We need to find the current branch
|
||||||
- git checkout `git branch --contains HEAD | grep -v '*'`
|
- git checkout `git branch --contains HEAD | grep -v '*'`
|
||||||
# Also tags for the root(s) of the minor version(s)
|
# Also tags for the root(s) of the minor version(s)
|
||||||
- git fetch origin --tags
|
- git fetch origin --tags
|
||||||
- mkdir ~/bin
|
- mkdir ~/bin
|
||||||
|
#
|
||||||
install:
|
install:
|
||||||
# Install arduino 1.6.4
|
# Install arduino 1.6.4
|
||||||
- wget http://downloads-02.arduino.cc/arduino-1.6.4-linux64.tar.xz
|
- wget http://downloads-02.arduino.cc/arduino-1.6.4-linux64.tar.xz
|
||||||
|
@ -26,188 +27,215 @@ install:
|
||||||
- mv LiquidCrystal_I2C/LiquidCrystal_I2C /usr/local/share/arduino/libraries/LiquidCrystal_I2C
|
- mv LiquidCrystal_I2C/LiquidCrystal_I2C /usr/local/share/arduino/libraries/LiquidCrystal_I2C
|
||||||
- git clone https://github.com/lincomatic/LiquidTWI2.git
|
- git clone https://github.com/lincomatic/LiquidTWI2.git
|
||||||
- mv LiquidTWI2 /usr/local/share/arduino/libraries/LiquidTWI2
|
- mv LiquidTWI2 /usr/local/share/arduino/libraries/LiquidTWI2
|
||||||
# Install astyle
|
#
|
||||||
- wget https://github.com/timonwong/astyle-mirror/archive/master.zip
|
|
||||||
- unzip master.zip
|
|
||||||
- cd astyle-mirror-master/build/gcc/
|
|
||||||
- make prefix=$HOME astyle install
|
|
||||||
before_script:
|
before_script:
|
||||||
# arduino requires an X server even with command line
|
# arduino requires an X server even with command line
|
||||||
# https://github.com/arduino/Arduino/issues/1981
|
# https://github.com/arduino/Arduino/issues/1981
|
||||||
- Xvfb :1 -screen 0 1024x768x16 &> xvfb.log &
|
- Xvfb :1 -screen 0 1024x768x16 &> xvfb.log &
|
||||||
# change back to home directory for compiling
|
# change back to home directory for compiling
|
||||||
- cd $TRAVIS_BUILD_DIR
|
- cd $TRAVIS_BUILD_DIR
|
||||||
# Check style
|
#
|
||||||
# ~/bin/astyle --recursive --options=.astylerc "Marlin/*.h" "Marlin/*.cpp"
|
|
||||||
script:
|
script:
|
||||||
# Abort on style errors
|
#
|
||||||
# if [ "0" != `find . -name "*.orig" | wc -l` ] ; then echo "Improperly styled source -- run astyle" ; exit -999; fi
|
# Backup Configuration.h, Configuration_adv.h, and pins_RAMPS_14.h
|
||||||
# Relaxed Travis check
|
#
|
||||||
# if [ "0" != `find . -name "*.orig" | wc -l` ] ; then echo "Improperly styled source -- run astyle" ; fi
|
|
||||||
# build default config
|
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
|
||||||
# backup configuration.h
|
|
||||||
- cp Marlin/Configuration.h Marlin/Configuration.h.backup
|
- cp Marlin/Configuration.h Marlin/Configuration.h.backup
|
||||||
- cp Marlin/Configuration_adv.h Marlin/Configuration_adv.h.backup
|
- cp Marlin/Configuration_adv.h Marlin/Configuration_adv.h.backup
|
||||||
- cp Marlin/pins_RAMPS_13.h Marlin/pins_RAMPS_13.h.backup
|
- cp Marlin/pins_RAMPS_14.h Marlin/pins_RAMPS_14.h.backup
|
||||||
# add sensor for bed
|
#
|
||||||
- sed -i 's/#define TEMP_SENSOR_BED 0/#define TEMP_SENSOR_BED 1/g' Marlin/Configuration.h
|
# Build with the default configurations
|
||||||
- rm -rf .build/
|
#
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- build_marlin
|
||||||
# change extruder numbers from 1 to 2
|
#
|
||||||
- sed -i 's/#define MOTHERBOARD BOARD_RAMPS_13_EFB/#define MOTHERBOARD BOARD_RAMPS_13_EEB/g' Marlin/Configuration.h
|
# Test heated bed temperature sensor
|
||||||
- sed -i 's/#define EXTRUDERS 1/#define EXTRUDERS 2/g' Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/#define TEMP_SENSOR_1 0/#define TEMP_SENSOR_1 1/g' Marlin/Configuration.h
|
- opt_set TEMP_SENSOR_BED 1
|
||||||
#- cat Marlin/Configuration.h
|
- build_marlin
|
||||||
- rm -rf .build/
|
#
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
# Test 2 extruders on basic RAMPS 1.4
|
||||||
# change extruder numbers from 2 to 3, needs to be a board with 3 extruders defined in pins.h
|
#
|
||||||
- sed -i 's/#define MOTHERBOARD BOARD_RAMPS_13_EEB/#define MOTHERBOARD BOARD_RUMBA/g' Marlin/Configuration.h
|
- opt_set MOTHERBOARD BOARD_RAMPS_14_EEB
|
||||||
- sed -i 's/#define EXTRUDERS 2/#define EXTRUDERS 3/g' Marlin/Configuration.h
|
- opt_set EXTRUDERS 2
|
||||||
- sed -i 's/#define TEMP_SENSOR_2 0/#define TEMP_SENSOR_2 1/g' Marlin/Configuration.h
|
- opt_set TEMP_SENSOR_1 1
|
||||||
- rm -rf .build/
|
- build_marlin
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
#
|
||||||
# enable PIDTEMPBED
|
# Test 3 extruders on RUMBA (can use any board with >=3 extruders defined)
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define PIDTEMPBED/#define PIDTEMPBED/g' Marlin/Configuration.h
|
- opt_set MOTHERBOARD BOARD_RUMBA
|
||||||
- rm -rf .build/
|
- opt_set EXTRUDERS 3
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- opt_set TEMP_SENSOR_2 1
|
||||||
# enable AUTO_BED_LEVELING
|
- build_marlin
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define ENABLE_AUTO_BED_LEVELING/#define ENABLE_AUTO_BED_LEVELING/g' Marlin/Configuration.h
|
# Test PIDTEMPBED
|
||||||
- rm -rf .build/
|
#
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- restore_configs
|
||||||
# enable AUTO_BED_LEVELING with servos
|
- opt_enable PIDTEMPBED
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
- build_marlin
|
||||||
- sed -i 's/\/\/#define ENABLE_AUTO_BED_LEVELING/#define ENABLE_AUTO_BED_LEVELING/g' Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define NUM_SERVOS/#define NUM_SERVOS/g' Marlin/Configuration.h
|
# Test AUTO_BED_LEVELING & DEBUG_LEVELING_FEATURE
|
||||||
- sed -i 's/\/\/#define Z_ENDSTOP_SERVO_NR/#define Z_ENDSTOP_SERVO_NR/g' Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define SERVO_ENDSTOP_ANGLES/#define SERVO_ENDSTOP_ANGLES/g' Marlin/Configuration.h
|
- restore_configs
|
||||||
- sed -i 's/\/\/#define DEACTIVATE_SERVOS_AFTER_MOVE/#define DEACTIVATE_SERVOS_AFTER_MOVE/g' Marlin/Configuration.h
|
- opt_enable ENABLE_AUTO_BED_LEVELING DEBUG_LEVELING_FEATURE
|
||||||
- rm -rf .build/
|
- build_marlin
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
#
|
||||||
# enable EEPROM_SETTINGS & EEPROM_CHITCHAT
|
# Test AUTO_BED_LEVELING & DEBUG_LEVELING_FEATURE with Servos
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define EEPROM_SETTINGS/#define EEPROM_SETTINGS/g' Marlin/Configuration.h
|
- opt_enable NUM_SERVOS Z_ENDSTOP_SERVO_NR SERVO_ENDSTOP_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
- sed -i 's/\/\/#define EEPROM_CHITCHAT/#define EEPROM_CHITCHAT/g' Marlin/Configuration.h
|
- build_marlin
|
||||||
- rm -rf .build/
|
#
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
# Test EEPROM_SETTINGS & EEPROM_CHITCHAT
|
||||||
|
#
|
||||||
|
- restore_configs
|
||||||
|
- opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT
|
||||||
|
- build_marlin
|
||||||
|
#
|
||||||
### LCDS ###
|
### LCDS ###
|
||||||
|
#
|
||||||
|
#
|
||||||
# ULTIMAKERCONTROLLER
|
# ULTIMAKERCONTROLLER
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define ULTIMAKERCONTROLLER/#define ULTIMAKERCONTROLLER/g' Marlin/Configuration.h
|
- restore_configs
|
||||||
- rm -rf .build/
|
- opt_enable ULTIMAKERCONTROLLER
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- build_marlin
|
||||||
|
#
|
||||||
# MAKRPANEL
|
# MAKRPANEL
|
||||||
# Needs to use melzi and sanguino hardware
|
# Needs to use Melzi and Sanguino hardware
|
||||||
#- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
#- sed -i 's/\/\/#define MAKRPANEL/#define MAKRPANEL/g' Marlin/Configuration.h
|
#- restore_configs
|
||||||
#- rm -rf .build/
|
#- opt_enable MAKRPANEL
|
||||||
#- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
#- build_marlin
|
||||||
|
#
|
||||||
# REPRAP_DISCOUNT_SMART_CONTROLLER
|
# REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define REPRAP_DISCOUNT_SMART_CONTROLLER/#define REPRAP_DISCOUNT_SMART_CONTROLLER/g' Marlin/Configuration.h
|
- restore_configs
|
||||||
- rm -rf .build/
|
- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- build_marlin
|
||||||
# G3D_PANE
|
#
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
# G3D_PANEL
|
||||||
- sed -i 's/\/\/#define G3D_PANEL/#define G3D_PANEL/g' Marlin/Configuration.h
|
#
|
||||||
- rm -rf .build/
|
- restore_configs
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- opt_enable G3D_PANEL SDSUPPORT
|
||||||
|
- build_marlin
|
||||||
|
#
|
||||||
# REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
# REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER/#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER/g' Marlin/Configuration.h
|
- restore_configs
|
||||||
- rm -rf .build/
|
- opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- build_marlin
|
||||||
|
#
|
||||||
# REPRAPWORLD_KEYPAD
|
# REPRAPWORLD_KEYPAD
|
||||||
|
#
|
||||||
# Cant find configuration details to get it to compile
|
# Cant find configuration details to get it to compile
|
||||||
#- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#- restore_configs
|
||||||
#- sed -i 's/\/\/#define ULTRA_LCD/#define ULTRA_LCD/g' Marlin/Configuration.h
|
#- opt_enable ULTRA_LCD REPRAPWORLD_KEYPAD REPRAPWORLD_KEYPAD_MOVE_STEP
|
||||||
#- sed -i 's/\/\/#define REPRAPWORLD_KEYPAD/#define REPRAPWORLD_KEYPAD/g' Marlin/Configuration.h
|
#- build_marlin
|
||||||
#- sed -i 's/\/\/#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0/#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0/g' Marlin/Configuration.h
|
#
|
||||||
#- rm -rf .build/
|
|
||||||
#- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
|
||||||
# RA_CONTROL_PANEL
|
# RA_CONTROL_PANEL
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define RA_CONTROL_PANEL/#define RA_CONTROL_PANEL/g' Marlin/Configuration.h
|
- restore_configs
|
||||||
- rm -rf .build/
|
- opt_enable RA_CONTROL_PANEL
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- build_marlin
|
||||||
|
#
|
||||||
### I2C PANELS ###
|
### I2C PANELS ###
|
||||||
|
#
|
||||||
# LCD_I2C_SAINSMART_YWROBOT
|
# LCD_I2C_SAINSMART_YWROBOT
|
||||||
# Failing at the moment needs different library
|
# Failing at the moment needs different library
|
||||||
#- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#- restore_configs
|
||||||
#- sed -i 's/\/\/#define LCD_I2C_SAINSMART_YWROBOT/#define LCD_I2C_SAINSMART_YWROBOT/g' Marlin/Configuration.h
|
#- opt_enable LCD_I2C_SAINSMART_YWROBOT
|
||||||
#- rm -rf .build/
|
#- build_marlin
|
||||||
#- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
#
|
||||||
# LCD_I2C_PANELOLU2
|
# LCD_I2C_PANELOLU2
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define LCD_I2C_PANELOLU2/#define LCD_I2C_PANELOLU2/g' Marlin/Configuration.h
|
- restore_configs
|
||||||
- rm -rf .build/
|
- opt_enable LCD_I2C_PANELOLU2
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- build_marlin
|
||||||
|
#
|
||||||
# LCD_I2C_VIKI
|
# LCD_I2C_VIKI
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define LCD_I2C_VIKI/#define LCD_I2C_VIKI/g' Marlin/Configuration.h
|
- restore_configs
|
||||||
- rm -rf .build/
|
- opt_enable LCD_I2C_VIKI
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- build_marlin
|
||||||
|
#
|
||||||
|
# LCM1602
|
||||||
|
#
|
||||||
|
- restore_configs
|
||||||
|
- opt_enable LCM1602
|
||||||
|
- build_marlin
|
||||||
|
#
|
||||||
|
# Enable FILAMENTCHANGEENABLE
|
||||||
|
#
|
||||||
|
- restore_configs
|
||||||
|
- opt_enable FILAMENTCHANGEENABLE ULTIMAKERCONTROLLER
|
||||||
|
- build_marlin
|
||||||
|
#
|
||||||
# Enable filament sensor
|
# Enable filament sensor
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define FILAMENT_SENSOR/#define FILAMENT_SENSOR/g' Marlin/Configuration.h
|
- restore_configs
|
||||||
- rm -rf .build/
|
- opt_enable FILAMENT_WIDTH_SENSOR
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- build_marlin
|
||||||
# Enable filament sensor with LCD display
|
#
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
# Enable filament sensor with LCD display
|
||||||
- sed -i 's/\/\/#define ULTIMAKERCONTROLLER/#define ULTIMAKERCONTROLLER/g' Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define FILAMENT_SENSOR/#define FILAMENT_SENSOR/g' Marlin/Configuration.h
|
- opt_enable ULTIMAKERCONTROLLER FILAMENT_LCD_DISPLAY
|
||||||
- sed -i 's/\/\/#define FILAMENT_LCD_DISPLAY/#define FILAMENT_LCD_DISPLAY/g' Marlin/Configuration.h
|
- build_marlin
|
||||||
- rm -rf .build/
|
#
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
|
||||||
# Enable COREXY
|
# Enable COREXY
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define COREXY/#define COREXY/g' Marlin/Configuration.h
|
- restore_configs
|
||||||
- rm -rf .build/
|
- opt_enable COREXY
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- build_marlin
|
||||||
|
#
|
||||||
# Enable COREXZ
|
# Enable COREXZ
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define COREXZ/#define COREXZ/g' Marlin/Configuration.h
|
- restore_configs
|
||||||
- rm -rf .build/
|
- opt_enable COREXZ
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- build_marlin
|
||||||
|
#
|
||||||
# Enable Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS
|
# Enable Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
- sed -i 's/\/\/#define Z_DUAL_STEPPER_DRIVERS/#define Z_DUAL_STEPPER_DRIVERS/g' Marlin/Configuration_adv.h
|
- restore_configs
|
||||||
- sed -i 's/\ \ \/\/\ \#define Z_DUAL_ENDSTOPS/#define Z_DUAL_ENDSTOPS/g' Marlin/Configuration_adv.h
|
- opt_enable_adv Z_DUAL_STEPPER_DRIVERS Z_DUAL_ENDSTOPS
|
||||||
- sed -i 's/#define X_MAX_PIN 2/#define X_MAX_PIN -1/g' Marlin/pins_RAMPS_13.h
|
- pins_set RAMPS_14 X_MAX_PIN -1
|
||||||
- sed -i 's/\ \ \ \ \#define Z2_MAX_PIN 36/#define Z2_MAX_PIN 2/g' Marlin/Configuration_adv.h
|
- opt_set_adv Z2_MAX_PIN 2
|
||||||
- rm -rf .build/
|
- build_marlin
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
#
|
||||||
- cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
#
|
||||||
- cp Marlin/Configuration_adv.h.backup Marlin/Configuration_adv.h
|
|
||||||
- cp Marlin/pins_RAMPS_13.h.backup Marlin/pins_RAMPS_13.h
|
|
||||||
######## Example Configurations ##############
|
######## Example Configurations ##############
|
||||||
|
#
|
||||||
# Delta Config (generic)
|
# Delta Config (generic)
|
||||||
- cp Marlin/example_configurations/delta/generic/Configuration* Marlin/
|
- restore_configs
|
||||||
- rm -rf .build/
|
- use_example_configs delta/generic
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- build_marlin
|
||||||
|
#
|
||||||
# Delta Config (generic) + ABL + ALLEN_KEY
|
# Delta Config (generic) + ABL + ALLEN_KEY
|
||||||
- cp Marlin/example_configurations/delta/generic/Configuration* Marlin/
|
#
|
||||||
- sed -i 's/#define DISABLE_MIN_ENDSTOPS/\/\/#define DISABLE_MIN_ENDSTOPS/g' Marlin/Configuration.h
|
- use_example_configs delta/generic
|
||||||
- sed -i 's/\/\/#define AUTO_BED_LEVELING_FEATURE/#define AUTO_BED_LEVELING_FEATURE/g' Marlin/Configuration.h
|
- opt_disable DISABLE_MIN_ENDSTOPS
|
||||||
- sed -i 's/\/\/#define Z_PROBE_ALLEN_KEY/#define Z_PROBE_ALLEN_KEY/g' Marlin/Configuration.h
|
- opt_enable AUTO_BED_LEVELING_FEATURE Z_PROBE_ALLEN_KEY
|
||||||
- rm -rf .build/
|
- build_marlin
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
#
|
||||||
# Delta Config (Mini Kossel)
|
# Delta Config (Mini Kossel)
|
||||||
- cp Marlin/example_configurations/delta/kossel_mini/Configuration* Marlin/
|
#
|
||||||
- rm -rf .build/
|
- use_example_configs delta/kossel_mini
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- build_marlin
|
||||||
|
#
|
||||||
# Makibox Config need to check board type for Teensy++ 2.0
|
# Makibox Config need to check board type for Teensy++ 2.0
|
||||||
#- cp Marlin/example_configurations/makibox/Configuration* Marlin/
|
#
|
||||||
#- rm -rf .build/
|
#- use_example_configs makibox
|
||||||
#- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
#- build_marlin
|
||||||
|
#
|
||||||
# SCARA Config
|
# SCARA Config
|
||||||
- cp Marlin/example_configurations/SCARA/Configuration* Marlin/
|
#
|
||||||
- rm -rf .build/
|
- use_example_configs SCARA
|
||||||
- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
- build_marlin
|
||||||
|
#
|
||||||
# tvrrug Config need to check board type for sanguino atmega644p
|
# tvrrug Config need to check board type for sanguino atmega644p
|
||||||
#- cp Marlin/example_configurations/tvrrug/Round2/Configuration* Marlin/
|
#
|
||||||
#- rm -rf .build/
|
#- use_example_configs tvrrug/Round2
|
||||||
#- DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
#- build_marlin
|
||||||
|
#
|
||||||
|
#
|
||||||
######## Board Types #############
|
######## Board Types #############
|
||||||
|
#
|
||||||
|
# To be added in nightly test branch
|
||||||
|
#
|
||||||
|
|
|
@ -95,7 +95,7 @@ rambo.build.variant=rambo
|
||||||
sanguino.name=Sanguino
|
sanguino.name=Sanguino
|
||||||
|
|
||||||
sanguino.upload.tool=arduino:avrdude
|
sanguino.upload.tool=arduino:avrdude
|
||||||
sanguino.upload.protocol=stk500
|
sanguino.upload.protocol=arduino
|
||||||
sanguino.upload.maximum_size=131072
|
sanguino.upload.maximum_size=131072
|
||||||
sanguino.upload.speed=57600
|
sanguino.upload.speed=57600
|
||||||
|
|
||||||
|
|
4
LinuxAddons/bin/build_marlin
Executable file
4
LinuxAddons/bin/build_marlin
Executable file
|
@ -0,0 +1,4 @@
|
||||||
|
#!/usr/bin/env bash
|
||||||
|
|
||||||
|
rm -rf .build/
|
||||||
|
DISPLAY=:1.0 ~/bin/arduino --verify --board marlin:avr:mega Marlin/Marlin.ino
|
5
LinuxAddons/bin/opt_disable
Executable file
5
LinuxAddons/bin/opt_disable
Executable file
|
@ -0,0 +1,5 @@
|
||||||
|
#!/usr/bin/env bash
|
||||||
|
|
||||||
|
for opt in "$@" ; do
|
||||||
|
eval "sed -i 's/\(\/\/ *\)*\(\#define *$opt\)/\/\/\2/g' Marlin/Configuration.h"
|
||||||
|
done
|
5
LinuxAddons/bin/opt_enable
Executable file
5
LinuxAddons/bin/opt_enable
Executable file
|
@ -0,0 +1,5 @@
|
||||||
|
#!/usr/bin/env bash
|
||||||
|
|
||||||
|
for opt in "$@" ; do
|
||||||
|
eval "sed -i 's/\/\/ *\(#define *$opt\)/\1/g' Marlin/Configuration.h"
|
||||||
|
done
|
5
LinuxAddons/bin/opt_enable_adv
Executable file
5
LinuxAddons/bin/opt_enable_adv
Executable file
|
@ -0,0 +1,5 @@
|
||||||
|
#!/usr/bin/env bash
|
||||||
|
|
||||||
|
for opt in "$@" ; do
|
||||||
|
eval "sed -i 's/\/\/ *\(#define *$opt\)/\1/g' Marlin/Configuration_adv.h"
|
||||||
|
done
|
3
LinuxAddons/bin/opt_set
Executable file
3
LinuxAddons/bin/opt_set
Executable file
|
@ -0,0 +1,3 @@
|
||||||
|
#!/usr/bin/env bash
|
||||||
|
|
||||||
|
eval "sed -i 's/\(#define *$1\) *.*$/\1 $2/g' Marlin/Configuration.h"
|
3
LinuxAddons/bin/opt_set_adv
Executable file
3
LinuxAddons/bin/opt_set_adv
Executable file
|
@ -0,0 +1,3 @@
|
||||||
|
#!/usr/bin/env bash
|
||||||
|
|
||||||
|
eval "sed -i 's/\(#define *$1\) *.*$/\1 $2/g' Marlin/Configuration_adv.h"
|
3
LinuxAddons/bin/pins_set
Executable file
3
LinuxAddons/bin/pins_set
Executable file
|
@ -0,0 +1,3 @@
|
||||||
|
#!/usr/bin/env bash
|
||||||
|
|
||||||
|
eval "sed -i 's/\(#define *$2\) *.*$/\1 $3/g' Marlin/pins_$1.h"
|
5
LinuxAddons/bin/restore_configs
Executable file
5
LinuxAddons/bin/restore_configs
Executable file
|
@ -0,0 +1,5 @@
|
||||||
|
#!/usr/bin/env bash
|
||||||
|
|
||||||
|
cp Marlin/Configuration.h.backup Marlin/Configuration.h
|
||||||
|
cp Marlin/Configuration_adv.h.backup Marlin/Configuration_adv.h
|
||||||
|
cp Marlin/pins_RAMPS_14.h.backup Marlin/pins_RAMPS_14.h
|
3
LinuxAddons/bin/use_example_configs
Executable file
3
LinuxAddons/bin/use_example_configs
Executable file
|
@ -0,0 +1,3 @@
|
||||||
|
#!/usr/bin/env bash
|
||||||
|
|
||||||
|
eval "cp Marlin/example_configurations/$1/Configuration* Marlin/"
|
|
@ -1,16 +1,48 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Conditionals.h
|
* Conditionals.h
|
||||||
* Defines that depend on configuration but are not editable.
|
* Defines that depend on configuration but are not editable.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef CONDITIONALS_H
|
#ifndef CONDITIONALS_H
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Miscellaneous
|
||||||
|
*/
|
||||||
#ifndef M_PI
|
#ifndef M_PI
|
||||||
#define M_PI 3.1415926536
|
#define M_PI 3.1415926536
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef CONFIGURATION_LCD // Get the LCD defines which are needed first
|
/**
|
||||||
|
* This value is used by M109 when tying to calculate a ballpark safe margin
|
||||||
|
* to prevent wait-forever situation.
|
||||||
|
*/
|
||||||
|
#ifndef EXTRUDE_MINTEMP
|
||||||
|
#define EXTRUDE_MINTEMP 170
|
||||||
|
#endif
|
||||||
|
|
||||||
#define PIN_EXISTS(PN) (defined(PN##_PIN) && PN##_PIN >= 0)
|
#ifndef CONFIGURATION_LCD // Get the LCD defines which are needed first
|
||||||
|
|
||||||
#define CONFIGURATION_LCD
|
#define CONFIGURATION_LCD
|
||||||
|
|
||||||
|
@ -45,11 +77,26 @@
|
||||||
#define DOGLCD // Support for I2C LCD 128x64 (Controller SSD1306 graphic Display Family)
|
#define DOGLCD // Support for I2C LCD 128x64 (Controller SSD1306 graphic Display Family)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#if ENABLED(PANEL_ONE)
|
#if ENABLED(PANEL_ONE)
|
||||||
#define ULTIMAKERCONTROLLER
|
#define ULTIMAKERCONTROLLER
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(BQ_LCD_SMART_CONTROLLER)
|
||||||
|
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
|
#ifndef ENCODER_PULSES_PER_STEP
|
||||||
|
#define ENCODER_PULSES_PER_STEP 4
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef ENCODER_STEPS_PER_MENU_ITEM
|
||||||
|
#define ENCODER_STEPS_PER_MENU_ITEM 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef LONG_FILENAME_HOST_SUPPORT
|
||||||
|
#define LONG_FILENAME_HOST_SUPPORT
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
|
#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
|
||||||
#define DOGLCD
|
#define DOGLCD
|
||||||
#define U8GLIB_ST7920
|
#define U8GLIB_ST7920
|
||||||
|
@ -135,28 +182,35 @@
|
||||||
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
|
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
|
||||||
|
|
||||||
#if ENABLED(SAV_3DLCD)
|
#if ENABLED(SAV_3DLCD)
|
||||||
#define SR_LCD_2W_NL // Non latching 2 wire shiftregister
|
#define SR_LCD_2W_NL // Non latching 2 wire shift register
|
||||||
#define ULTIPANEL
|
#define ULTIPANEL
|
||||||
#define NEWPANEL
|
#define NEWPANEL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(DOGLCD) // Change number of lines to match the DOG graphic display
|
||||||
|
#ifndef LCD_WIDTH
|
||||||
|
#define LCD_WIDTH 22
|
||||||
|
#endif
|
||||||
|
#ifndef LCD_HEIGHT
|
||||||
|
#define LCD_HEIGHT 5
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#if ENABLED(ULTIPANEL)
|
#if ENABLED(ULTIPANEL)
|
||||||
#define NEWPANEL //enable this if you have a click-encoder panel
|
#define NEWPANEL //enable this if you have a click-encoder panel
|
||||||
#define ULTRA_LCD
|
#define ULTRA_LCD
|
||||||
#if ENABLED(DOGLCD) // Change number of lines to match the DOG graphic display
|
#ifndef LCD_WIDTH
|
||||||
#define LCD_WIDTH 22
|
|
||||||
#define LCD_HEIGHT 5
|
|
||||||
#else
|
|
||||||
#define LCD_WIDTH 20
|
#define LCD_WIDTH 20
|
||||||
|
#endif
|
||||||
|
#ifndef LCD_HEIGHT
|
||||||
#define LCD_HEIGHT 4
|
#define LCD_HEIGHT 4
|
||||||
#endif
|
#endif
|
||||||
#else //no panel but just LCD
|
#else //no panel but just LCD
|
||||||
#if ENABLED(ULTRA_LCD)
|
#if ENABLED(ULTRA_LCD)
|
||||||
#if ENABLED(DOGLCD) // Change number of lines to match the 128x64 graphics display
|
#ifndef LCD_WIDTH
|
||||||
#define LCD_WIDTH 22
|
|
||||||
#define LCD_HEIGHT 5
|
|
||||||
#else
|
|
||||||
#define LCD_WIDTH 16
|
#define LCD_WIDTH 16
|
||||||
|
#endif
|
||||||
|
#ifndef LCD_HEIGHT
|
||||||
#define LCD_HEIGHT 2
|
#define LCD_HEIGHT 2
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
@ -221,20 +275,28 @@
|
||||||
#include "Arduino.h"
|
#include "Arduino.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* ENDSTOPPULLUPS
|
* Set ENDSTOPPULLUPS for unused endstop switches
|
||||||
*/
|
*/
|
||||||
#if ENABLED(ENDSTOPPULLUPS)
|
#if ENABLED(ENDSTOPPULLUPS)
|
||||||
#if DISABLED(DISABLE_MAX_ENDSTOPS)
|
#if ENABLED(USE_XMAX_PLUG)
|
||||||
#define ENDSTOPPULLUP_XMAX
|
#define ENDSTOPPULLUP_XMAX
|
||||||
|
#endif
|
||||||
|
#if ENABLED(USE_YMAX_PLUG)
|
||||||
#define ENDSTOPPULLUP_YMAX
|
#define ENDSTOPPULLUP_YMAX
|
||||||
|
#endif
|
||||||
|
#if ENABLED(USE_ZMAX_PLUG)
|
||||||
#define ENDSTOPPULLUP_ZMAX
|
#define ENDSTOPPULLUP_ZMAX
|
||||||
#endif
|
#endif
|
||||||
#if DISABLED(DISABLE_MIN_ENDSTOPS)
|
#if ENABLED(USE_XMIN_PLUG)
|
||||||
#define ENDSTOPPULLUP_XMIN
|
#define ENDSTOPPULLUP_XMIN
|
||||||
|
#endif
|
||||||
|
#if ENABLED(USE_YMIN_PLUG)
|
||||||
#define ENDSTOPPULLUP_YMIN
|
#define ENDSTOPPULLUP_YMIN
|
||||||
|
#endif
|
||||||
|
#if ENABLED(USE_ZMIN_PLUG)
|
||||||
#define ENDSTOPPULLUP_ZMIN
|
#define ENDSTOPPULLUP_ZMIN
|
||||||
#endif
|
#endif
|
||||||
#if DISABLED(DISABLE_Z_MIN_PROBE_ENDSTOP)
|
#if ENABLED(DISABLE_Z_MIN_PROBE_ENDSTOP)
|
||||||
#define ENDSTOPPULLUP_ZMIN_PROBE
|
#define ENDSTOPPULLUP_ZMIN_PROBE
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
@ -242,9 +304,20 @@
|
||||||
/**
|
/**
|
||||||
* Axis lengths
|
* Axis lengths
|
||||||
*/
|
*/
|
||||||
#define X_MAX_LENGTH (X_MAX_POS - X_MIN_POS)
|
#define X_MAX_LENGTH (X_MAX_POS - (X_MIN_POS))
|
||||||
#define Y_MAX_LENGTH (Y_MAX_POS - Y_MIN_POS)
|
#define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS))
|
||||||
#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
|
#define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS))
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CoreXY and CoreXZ
|
||||||
|
*/
|
||||||
|
#if ENABLED(COREXY)
|
||||||
|
#define CORE_AXIS_2 B_AXIS
|
||||||
|
#define CORE_AXIS_3 Z_AXIS
|
||||||
|
#elif ENABLED(COREXZ)
|
||||||
|
#define CORE_AXIS_2 C_AXIS
|
||||||
|
#define CORE_AXIS_3 Y_AXIS
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* SCARA
|
* SCARA
|
||||||
|
@ -263,8 +336,8 @@
|
||||||
#define Z_HOME_POS MANUAL_Z_HOME_POS
|
#define Z_HOME_POS MANUAL_Z_HOME_POS
|
||||||
#else //!MANUAL_HOME_POSITIONS – Use home switch positions based on homing direction and travel limits
|
#else //!MANUAL_HOME_POSITIONS – Use home switch positions based on homing direction and travel limits
|
||||||
#if ENABLED(BED_CENTER_AT_0_0)
|
#if ENABLED(BED_CENTER_AT_0_0)
|
||||||
#define X_HOME_POS X_MAX_LENGTH * X_HOME_DIR * 0.5
|
#define X_HOME_POS (X_MAX_LENGTH) * (X_HOME_DIR) * 0.5
|
||||||
#define Y_HOME_POS Y_MAX_LENGTH * Y_HOME_DIR * 0.5
|
#define Y_HOME_POS (Y_MAX_LENGTH) * (Y_HOME_DIR) * 0.5
|
||||||
#else
|
#else
|
||||||
#define X_HOME_POS (X_HOME_DIR < 0 ? X_MIN_POS : X_MAX_POS)
|
#define X_HOME_POS (X_HOME_DIR < 0 ? X_MIN_POS : X_MAX_POS)
|
||||||
#define Y_HOME_POS (Y_HOME_DIR < 0 ? Y_MIN_POS : Y_MAX_POS)
|
#define Y_HOME_POS (Y_HOME_DIR < 0 ? Y_MIN_POS : Y_MAX_POS)
|
||||||
|
@ -283,7 +356,7 @@
|
||||||
#define MAX_PROBE_Y (min(Y_MAX_POS, Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
|
#define MAX_PROBE_Y (min(Y_MAX_POS, Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define SERVO_LEVELING (defined(AUTO_BED_LEVELING_FEATURE) && defined(Z_ENDSTOP_SERVO_NR))
|
#define SERVO_LEVELING (ENABLED(AUTO_BED_LEVELING_FEATURE) && defined(Z_ENDSTOP_SERVO_NR) && Z_ENDSTOP_SERVO_NR >= 0)
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Sled Options
|
* Sled Options
|
||||||
|
@ -292,6 +365,13 @@
|
||||||
#define Z_SAFE_HOMING
|
#define Z_SAFE_HOMING
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Avoid double-negatives for enabling features
|
||||||
|
*/
|
||||||
|
#if DISABLED(DISABLE_HOST_KEEPALIVE)
|
||||||
|
#define HOST_KEEPALIVE_FEATURE
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* MAX_STEP_FREQUENCY differs for TOSHIBA
|
* MAX_STEP_FREQUENCY differs for TOSHIBA
|
||||||
*/
|
*/
|
||||||
|
@ -312,14 +392,30 @@
|
||||||
* Advance calculated values
|
* Advance calculated values
|
||||||
*/
|
*/
|
||||||
#if ENABLED(ADVANCE)
|
#if ENABLED(ADVANCE)
|
||||||
#define EXTRUSION_AREA (0.25 * D_FILAMENT * D_FILAMENT * M_PI)
|
#define EXTRUSION_AREA (0.25 * (D_FILAMENT) * (D_FILAMENT) * M_PI)
|
||||||
#define STEPS_PER_CUBIC_MM_E (axis_steps_per_unit[E_AXIS] / EXTRUSION_AREA)
|
#define STEPS_PER_CUBIC_MM_E (axis_steps_per_unit[E_AXIS] / (EXTRUSION_AREA))
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(ULTIPANEL) && DISABLED(ELB_FULL_GRAPHIC_CONTROLLER)
|
#if ENABLED(ULTIPANEL) && DISABLED(ELB_FULL_GRAPHIC_CONTROLLER)
|
||||||
#undef SD_DETECT_INVERTED
|
#undef SD_DETECT_INVERTED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set defaults for missing (newer) options
|
||||||
|
*/
|
||||||
|
#ifndef DISABLE_INACTIVE_X
|
||||||
|
#define DISABLE_INACTIVE_X DISABLE_X
|
||||||
|
#endif
|
||||||
|
#ifndef DISABLE_INACTIVE_Y
|
||||||
|
#define DISABLE_INACTIVE_Y DISABLE_Y
|
||||||
|
#endif
|
||||||
|
#ifndef DISABLE_INACTIVE_Z
|
||||||
|
#define DISABLE_INACTIVE_Z DISABLE_Z
|
||||||
|
#endif
|
||||||
|
#ifndef DISABLE_INACTIVE_E
|
||||||
|
#define DISABLE_INACTIVE_E DISABLE_E
|
||||||
|
#endif
|
||||||
|
|
||||||
// Power Signal Control Definitions
|
// Power Signal Control Definitions
|
||||||
// By default use ATX definition
|
// By default use ATX definition
|
||||||
#ifndef POWER_SUPPLY
|
#ifndef POWER_SUPPLY
|
||||||
|
@ -337,7 +433,10 @@
|
||||||
/**
|
/**
|
||||||
* Temp Sensor defines
|
* Temp Sensor defines
|
||||||
*/
|
*/
|
||||||
#if TEMP_SENSOR_0 == -2
|
#if TEMP_SENSOR_0 == -3
|
||||||
|
#define HEATER_0_USES_MAX6675
|
||||||
|
#define MAX6675_IS_MAX31855
|
||||||
|
#elif TEMP_SENSOR_0 == -2
|
||||||
#define HEATER_0_USES_MAX6675
|
#define HEATER_0_USES_MAX6675
|
||||||
#elif TEMP_SENSOR_0 == -1
|
#elif TEMP_SENSOR_0 == -1
|
||||||
#define HEATER_0_USES_AD595
|
#define HEATER_0_USES_AD595
|
||||||
|
@ -349,7 +448,9 @@
|
||||||
#define HEATER_0_USES_THERMISTOR
|
#define HEATER_0_USES_THERMISTOR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if TEMP_SENSOR_1 == -1
|
#if TEMP_SENSOR_1 <= -2
|
||||||
|
#error MAX6675 / MAX31855 Thermocouples not supported for TEMP_SENSOR_1
|
||||||
|
#elif TEMP_SENSOR_1 == -1
|
||||||
#define HEATER_1_USES_AD595
|
#define HEATER_1_USES_AD595
|
||||||
#elif TEMP_SENSOR_1 == 0
|
#elif TEMP_SENSOR_1 == 0
|
||||||
#undef HEATER_1_MINTEMP
|
#undef HEATER_1_MINTEMP
|
||||||
|
@ -359,7 +460,9 @@
|
||||||
#define HEATER_1_USES_THERMISTOR
|
#define HEATER_1_USES_THERMISTOR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if TEMP_SENSOR_2 == -1
|
#if TEMP_SENSOR_2 <= -2
|
||||||
|
#error MAX6675 / MAX31855 Thermocouples not supported for TEMP_SENSOR_2
|
||||||
|
#elif TEMP_SENSOR_2 == -1
|
||||||
#define HEATER_2_USES_AD595
|
#define HEATER_2_USES_AD595
|
||||||
#elif TEMP_SENSOR_2 == 0
|
#elif TEMP_SENSOR_2 == 0
|
||||||
#undef HEATER_2_MINTEMP
|
#undef HEATER_2_MINTEMP
|
||||||
|
@ -369,7 +472,9 @@
|
||||||
#define HEATER_2_USES_THERMISTOR
|
#define HEATER_2_USES_THERMISTOR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if TEMP_SENSOR_3 == -1
|
#if TEMP_SENSOR_3 <= -2
|
||||||
|
#error MAX6675 / MAX31855 Thermocouples not supported for TEMP_SENSOR_3
|
||||||
|
#elif TEMP_SENSOR_3 == -1
|
||||||
#define HEATER_3_USES_AD595
|
#define HEATER_3_USES_AD595
|
||||||
#elif TEMP_SENSOR_3 == 0
|
#elif TEMP_SENSOR_3 == 0
|
||||||
#undef HEATER_3_MINTEMP
|
#undef HEATER_3_MINTEMP
|
||||||
|
@ -379,7 +484,9 @@
|
||||||
#define HEATER_3_USES_THERMISTOR
|
#define HEATER_3_USES_THERMISTOR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if TEMP_SENSOR_BED == -1
|
#if TEMP_SENSOR_BED <= -2
|
||||||
|
#error MAX6675 / MAX31855 Thermocouples not supported for TEMP_SENSOR_BED
|
||||||
|
#elif TEMP_SENSOR_BED == -1
|
||||||
#define BED_USES_AD595
|
#define BED_USES_AD595
|
||||||
#elif TEMP_SENSOR_BED == 0
|
#elif TEMP_SENSOR_BED == 0
|
||||||
#undef BED_MINTEMP
|
#undef BED_MINTEMP
|
||||||
|
@ -404,14 +511,55 @@
|
||||||
|
|
||||||
#define ARRAY_BY_EXTRUDERS1(v1) ARRAY_BY_EXTRUDERS(v1, v1, v1, v1)
|
#define ARRAY_BY_EXTRUDERS1(v1) ARRAY_BY_EXTRUDERS(v1, v1, v1, v1)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Z_DUAL_ENDSTOPS endstop reassignment
|
||||||
|
*/
|
||||||
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
|
#define _XMIN_ 100
|
||||||
|
#define _YMIN_ 200
|
||||||
|
#define _ZMIN_ 300
|
||||||
|
#define _XMAX_ 101
|
||||||
|
#define _YMAX_ 201
|
||||||
|
#define _ZMAX_ 301
|
||||||
|
const bool Z2_MAX_ENDSTOP_INVERTING =
|
||||||
|
#if Z2_USE_ENDSTOP == _XMAX_
|
||||||
|
X_MAX_ENDSTOP_INVERTING
|
||||||
|
#define Z2_MAX_PIN X_MAX_PIN
|
||||||
|
#undef USE_XMAX_PLUG
|
||||||
|
#elif Z2_USE_ENDSTOP == _YMAX_
|
||||||
|
Y_MAX_ENDSTOP_INVERTING
|
||||||
|
#define Z2_MAX_PIN Y_MAX_PIN
|
||||||
|
#undef USE_YMAX_PLUG
|
||||||
|
#elif Z2_USE_ENDSTOP == _ZMAX_
|
||||||
|
Z_MAX_ENDSTOP_INVERTING
|
||||||
|
#define Z2_MAX_PIN Z_MAX_PIN
|
||||||
|
#undef USE_ZMAX_PLUG
|
||||||
|
#elif Z2_USE_ENDSTOP == _XMIN_
|
||||||
|
X_MIN_ENDSTOP_INVERTING
|
||||||
|
#define Z2_MAX_PIN X_MIN_PIN
|
||||||
|
#undef USE_XMIN_PLUG
|
||||||
|
#elif Z2_USE_ENDSTOP == _YMIN_
|
||||||
|
Y_MIN_ENDSTOP_INVERTING
|
||||||
|
#define Z2_MAX_PIN Y_MIN_PIN
|
||||||
|
#undef USE_YMIN_PLUG
|
||||||
|
#elif Z2_USE_ENDSTOP == _ZMIN_
|
||||||
|
Z_MIN_ENDSTOP_INVERTING
|
||||||
|
#define Z2_MAX_PIN Z_MIN_PIN
|
||||||
|
#undef USE_ZMIN_PLUG
|
||||||
|
#else
|
||||||
|
0
|
||||||
|
#endif
|
||||||
|
;
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Shorthand for pin tests, used wherever needed
|
* Shorthand for pin tests, used wherever needed
|
||||||
*/
|
*/
|
||||||
#define HAS_TEMP_0 (PIN_EXISTS(TEMP_0) && TEMP_SENSOR_0 != 0 && TEMP_SENSOR_0 != -2)
|
#define HAS_TEMP_0 (PIN_EXISTS(TEMP_0) && TEMP_SENSOR_0 != 0 && TEMP_SENSOR_0 > -2)
|
||||||
#define HAS_TEMP_1 (PIN_EXISTS(TEMP_1) && TEMP_SENSOR_1 != 0)
|
#define HAS_TEMP_1 (PIN_EXISTS(TEMP_1) && TEMP_SENSOR_1 != 0 && TEMP_SENSOR_1 > -2)
|
||||||
#define HAS_TEMP_2 (PIN_EXISTS(TEMP_2) && TEMP_SENSOR_2 != 0)
|
#define HAS_TEMP_2 (PIN_EXISTS(TEMP_2) && TEMP_SENSOR_2 != 0 && TEMP_SENSOR_2 > -2)
|
||||||
#define HAS_TEMP_3 (PIN_EXISTS(TEMP_3) && TEMP_SENSOR_3 != 0)
|
#define HAS_TEMP_3 (PIN_EXISTS(TEMP_3) && TEMP_SENSOR_3 != 0 && TEMP_SENSOR_3 > -2)
|
||||||
#define HAS_TEMP_BED (PIN_EXISTS(TEMP_BED) && TEMP_SENSOR_BED != 0)
|
#define HAS_TEMP_BED (PIN_EXISTS(TEMP_BED) && TEMP_SENSOR_BED != 0 && TEMP_SENSOR_BED > -2)
|
||||||
#define HAS_HEATER_0 (PIN_EXISTS(HEATER_0))
|
#define HAS_HEATER_0 (PIN_EXISTS(HEATER_0))
|
||||||
#define HAS_HEATER_1 (PIN_EXISTS(HEATER_1))
|
#define HAS_HEATER_1 (PIN_EXISTS(HEATER_1))
|
||||||
#define HAS_HEATER_2 (PIN_EXISTS(HEATER_2))
|
#define HAS_HEATER_2 (PIN_EXISTS(HEATER_2))
|
||||||
|
@ -422,14 +570,16 @@
|
||||||
#define HAS_AUTO_FAN_2 (PIN_EXISTS(EXTRUDER_2_AUTO_FAN))
|
#define HAS_AUTO_FAN_2 (PIN_EXISTS(EXTRUDER_2_AUTO_FAN))
|
||||||
#define HAS_AUTO_FAN_3 (PIN_EXISTS(EXTRUDER_3_AUTO_FAN))
|
#define HAS_AUTO_FAN_3 (PIN_EXISTS(EXTRUDER_3_AUTO_FAN))
|
||||||
#define HAS_AUTO_FAN (HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3)
|
#define HAS_AUTO_FAN (HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3)
|
||||||
#define HAS_FAN (PIN_EXISTS(FAN))
|
#define HAS_FAN0 (PIN_EXISTS(FAN))
|
||||||
|
#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)
|
||||||
|
#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)
|
||||||
#define HAS_CONTROLLERFAN (PIN_EXISTS(CONTROLLERFAN))
|
#define HAS_CONTROLLERFAN (PIN_EXISTS(CONTROLLERFAN))
|
||||||
#define HAS_SERVOS (defined(NUM_SERVOS) && NUM_SERVOS > 0)
|
#define HAS_SERVOS (defined(NUM_SERVOS) && NUM_SERVOS > 0)
|
||||||
#define HAS_SERVO_0 (PIN_EXISTS(SERVO0))
|
#define HAS_SERVO_0 (PIN_EXISTS(SERVO0))
|
||||||
#define HAS_SERVO_1 (PIN_EXISTS(SERVO1))
|
#define HAS_SERVO_1 (PIN_EXISTS(SERVO1))
|
||||||
#define HAS_SERVO_2 (PIN_EXISTS(SERVO2))
|
#define HAS_SERVO_2 (PIN_EXISTS(SERVO2))
|
||||||
#define HAS_SERVO_3 (PIN_EXISTS(SERVO3))
|
#define HAS_SERVO_3 (PIN_EXISTS(SERVO3))
|
||||||
#define HAS_FILAMENT_SENSOR (ENABLED(FILAMENT_SENSOR) && PIN_EXISTS(FILWIDTH))
|
#define HAS_FILAMENT_WIDTH_SENSOR (PIN_EXISTS(FILWIDTH))
|
||||||
#define HAS_FILRUNOUT (PIN_EXISTS(FILRUNOUT))
|
#define HAS_FILRUNOUT (PIN_EXISTS(FILRUNOUT))
|
||||||
#define HAS_HOME (PIN_EXISTS(HOME))
|
#define HAS_HOME (PIN_EXISTS(HOME))
|
||||||
#define HAS_KILL (PIN_EXISTS(KILL))
|
#define HAS_KILL (PIN_EXISTS(KILL))
|
||||||
|
@ -462,6 +612,7 @@
|
||||||
#define HAS_E1_ENABLE (PIN_EXISTS(E1_ENABLE))
|
#define HAS_E1_ENABLE (PIN_EXISTS(E1_ENABLE))
|
||||||
#define HAS_E2_ENABLE (PIN_EXISTS(E2_ENABLE))
|
#define HAS_E2_ENABLE (PIN_EXISTS(E2_ENABLE))
|
||||||
#define HAS_E3_ENABLE (PIN_EXISTS(E3_ENABLE))
|
#define HAS_E3_ENABLE (PIN_EXISTS(E3_ENABLE))
|
||||||
|
#define HAS_E4_ENABLE (PIN_EXISTS(E4_ENABLE))
|
||||||
#define HAS_X_DIR (PIN_EXISTS(X_DIR))
|
#define HAS_X_DIR (PIN_EXISTS(X_DIR))
|
||||||
#define HAS_X2_DIR (PIN_EXISTS(X2_DIR))
|
#define HAS_X2_DIR (PIN_EXISTS(X2_DIR))
|
||||||
#define HAS_Y_DIR (PIN_EXISTS(Y_DIR))
|
#define HAS_Y_DIR (PIN_EXISTS(Y_DIR))
|
||||||
|
@ -472,6 +623,7 @@
|
||||||
#define HAS_E1_DIR (PIN_EXISTS(E1_DIR))
|
#define HAS_E1_DIR (PIN_EXISTS(E1_DIR))
|
||||||
#define HAS_E2_DIR (PIN_EXISTS(E2_DIR))
|
#define HAS_E2_DIR (PIN_EXISTS(E2_DIR))
|
||||||
#define HAS_E3_DIR (PIN_EXISTS(E3_DIR))
|
#define HAS_E3_DIR (PIN_EXISTS(E3_DIR))
|
||||||
|
#define HAS_E4_DIR (PIN_EXISTS(E4_DIR))
|
||||||
#define HAS_X_STEP (PIN_EXISTS(X_STEP))
|
#define HAS_X_STEP (PIN_EXISTS(X_STEP))
|
||||||
#define HAS_X2_STEP (PIN_EXISTS(X2_STEP))
|
#define HAS_X2_STEP (PIN_EXISTS(X2_STEP))
|
||||||
#define HAS_Y_STEP (PIN_EXISTS(Y_STEP))
|
#define HAS_Y_STEP (PIN_EXISTS(Y_STEP))
|
||||||
|
@ -482,6 +634,11 @@
|
||||||
#define HAS_E1_STEP (PIN_EXISTS(E1_STEP))
|
#define HAS_E1_STEP (PIN_EXISTS(E1_STEP))
|
||||||
#define HAS_E2_STEP (PIN_EXISTS(E2_STEP))
|
#define HAS_E2_STEP (PIN_EXISTS(E2_STEP))
|
||||||
#define HAS_E3_STEP (PIN_EXISTS(E3_STEP))
|
#define HAS_E3_STEP (PIN_EXISTS(E3_STEP))
|
||||||
|
#define HAS_E4_STEP (PIN_EXISTS(E4_STEP))
|
||||||
|
|
||||||
|
#define HAS_MOTOR_CURRENT_PWM (PIN_EXISTS(MOTOR_CURRENT_PWM_XY) || PIN_EXISTS(MOTOR_CURRENT_PWM_Z) || PIN_EXISTS(MOTOR_CURRENT_PWM_E))
|
||||||
|
|
||||||
|
#define HAS_TEMP_HOTEND (HAS_TEMP_0 || ENABLED(HEATER_0_USES_MAX6675))
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Helper Macros for heaters and extruder fan
|
* Helper Macros for heaters and extruder fan
|
||||||
|
@ -504,10 +661,32 @@
|
||||||
#if HAS_HEATER_BED
|
#if HAS_HEATER_BED
|
||||||
#define WRITE_HEATER_BED(v) WRITE(HEATER_BED_PIN, v)
|
#define WRITE_HEATER_BED(v) WRITE(HEATER_BED_PIN, v)
|
||||||
#endif
|
#endif
|
||||||
#if HAS_FAN
|
|
||||||
#define WRITE_FAN(v) WRITE(FAN_PIN, v)
|
/**
|
||||||
|
* Up to 3 PWM fans
|
||||||
|
*/
|
||||||
|
#if HAS_FAN2
|
||||||
|
#define FAN_COUNT 3
|
||||||
|
#elif HAS_FAN1
|
||||||
|
#define FAN_COUNT 2
|
||||||
|
#elif HAS_FAN0
|
||||||
|
#define FAN_COUNT 1
|
||||||
|
#else
|
||||||
|
#define FAN_COUNT 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_FAN0
|
||||||
|
#define WRITE_FAN(v) WRITE(FAN_PIN, v)
|
||||||
|
#define WRITE_FAN0(v) WRITE_FAN(v)
|
||||||
|
#endif
|
||||||
|
#if HAS_FAN1
|
||||||
|
#define WRITE_FAN1(v) WRITE(FAN1_PIN, v)
|
||||||
|
#endif
|
||||||
|
#if HAS_FAN2
|
||||||
|
#define WRITE_FAN2(v) WRITE(FAN2_PIN, v)
|
||||||
|
#endif
|
||||||
|
#define WRITE_FAN_N(n, v) WRITE_FAN##n(v)
|
||||||
|
|
||||||
#define HAS_BUZZER (PIN_EXISTS(BEEPER) || defined(LCD_USE_I2C_BUZZER))
|
#define HAS_BUZZER (PIN_EXISTS(BEEPER) || defined(LCD_USE_I2C_BUZZER))
|
||||||
|
|
||||||
#if defined(NUM_SERVOS) && NUM_SERVOS > 0
|
#if defined(NUM_SERVOS) && NUM_SERVOS > 0
|
||||||
|
@ -526,5 +705,10 @@
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#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) )
|
||||||
|
#define HAS_Z_MIN_PROBE
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif //CONFIGURATION_LCD
|
#endif //CONFIGURATION_LCD
|
||||||
#endif //CONDITIONALS_H
|
#endif //CONDITIONALS_H
|
||||||
|
|
|
@ -1,3 +1,40 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -7,8 +44,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -16,11 +55,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -70,7 +105,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// The following define selects which electronics board you have.
|
// The following define selects which electronics board you have.
|
||||||
// Please choose the name from boards.h that matches your setup
|
// Please choose the name from boards.h that matches your setup
|
||||||
#ifndef MOTHERBOARD
|
#ifndef MOTHERBOARD
|
||||||
#define MOTHERBOARD BOARD_RAMPS_13_EFB
|
#define MOTHERBOARD BOARD_RAMPS_14_EFB
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Optional custom name for your RepStrap or other custom machine
|
// Optional custom name for your RepStrap or other custom machine
|
||||||
|
@ -110,6 +145,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -129,6 +165,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -144,7 +181,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 1
|
#define TEMP_SENSOR_0 1
|
||||||
#define TEMP_SENSOR_1 0
|
#define TEMP_SENSOR_1 0
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
|
@ -178,14 +215,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define HEATER_3_MAXTEMP 275
|
#define HEATER_3_MAXTEMP 275
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
|
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
|
||||||
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
|
//#define BED_WATTS (12.0*12.0/1.1) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -197,6 +229,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
|
@ -247,19 +280,19 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
|
|
||||||
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||||
#define DEFAULT_bedKp 10.00
|
#define DEFAULT_bedKp 10.00
|
||||||
#define DEFAULT_bedKi .023
|
#define DEFAULT_bedKi .023
|
||||||
#define DEFAULT_bedKd 305.4
|
#define DEFAULT_bedKd 305.4
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from pidautotune
|
//from pidautotune
|
||||||
//#define DEFAULT_bedKp 97.1
|
//#define DEFAULT_bedKp 97.1
|
||||||
//#define DEFAULT_bedKi 1.41
|
//#define DEFAULT_bedKi 1.41
|
||||||
|
@ -284,16 +317,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -314,8 +346,22 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
#define USE_XMIN_PLUG
|
||||||
|
#define USE_YMIN_PLUG
|
||||||
|
#define USE_ZMIN_PLUG
|
||||||
|
//#define USE_XMAX_PLUG
|
||||||
|
//#define USE_YMAX_PLUG
|
||||||
|
//#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -338,13 +384,53 @@ const bool X_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
//#define DISABLE_MAX_ENDSTOPS
|
|
||||||
//#define DISABLE_MIN_ENDSTOPS
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -354,11 +440,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z false
|
#define DISABLE_Z false
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -381,6 +469,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define INVERT_E3_DIR false
|
#define INVERT_E3_DIR false
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
@ -416,24 +506,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
|
||||||
#define MESH_MIN_Y 10
|
#define MESH_MIN_Y 10
|
||||||
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
|
#define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -444,7 +536,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
//#define DEBUG_LEVELING_FEATURE
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
|
@ -456,7 +548,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -478,25 +570,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X 15
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y 180
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X 15
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y 20
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X 170
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER 10 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER 10 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER 0 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
|
@ -504,17 +608,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
||||||
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
//#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
//If you have enabled the Bed Auto Leveling and are using the same Z Probe for Z Homing,
|
#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
//it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
|
|
||||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
|
@ -528,37 +644,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
|
||||||
|
@ -632,6 +717,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -652,13 +745,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
@ -666,12 +759,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
//#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)
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
|
||||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
||||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
|
@ -688,13 +781,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -709,7 +802,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
@ -732,6 +825,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -745,7 +840,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
// SSD1306 OLED generic display support
|
// SSD1306 OLED generic display support
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define U8GLIB_SSD1306
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
|
@ -757,7 +852,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
//#define FAST_PWM_FAN
|
//#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
@ -837,21 +932,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#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
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
|
|
||||||
//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.
|
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
|
@ -1,3 +1,35 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration_adv.h
|
||||||
|
*
|
||||||
|
* Advanced settings.
|
||||||
|
* Only change these if you know exactly what you're doing.
|
||||||
|
* Some of these settings can damage your printer if improperly set!
|
||||||
|
*
|
||||||
|
* Basic settings can be found in Configuration.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
|
|
||||||
|
@ -9,13 +41,26 @@
|
||||||
//=============================Thermal Settings ============================
|
//=============================Thermal Settings ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
#if DISABLED(PIDTEMPBED)
|
||||||
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||||
|
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||||
|
#define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection parameters
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
|
*
|
||||||
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
|
*
|
||||||
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
|
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
||||||
|
* the firmware will halt the machine as a safety precaution.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
|
||||||
*/
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
||||||
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
||||||
|
@ -26,11 +71,19 @@
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* but only if the current temperature is far enough below the target for a reliable test.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
|
||||||
|
* WATCH_TEMP_INCREASE should not be below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 16 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 4 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Thermal Protection parameters for the bed
|
||||||
|
* are like the above for the hotends.
|
||||||
|
* WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
|
||||||
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_BED)
|
#if ENABLED(THERMAL_PROTECTION_BED)
|
||||||
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
@ -52,7 +105,7 @@
|
||||||
* The maximum buffered steps/sec of the extruder motor is called "se".
|
* The maximum buffered steps/sec of the extruder motor is called "se".
|
||||||
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
||||||
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
||||||
* mintemp and maxtemp. Turn this off by excuting M109 without F*
|
* mintemp and maxtemp. Turn this off by executing M109 without F*
|
||||||
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
||||||
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
||||||
*/
|
*/
|
||||||
|
@ -148,9 +201,7 @@
|
||||||
//#define Z_DUAL_ENDSTOPS
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_MAX_PIN 36 //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36)
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
const bool Z2_MAX_ENDSTOP_INVERTING = false;
|
|
||||||
#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.
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
#endif // Z_DUAL_STEPPER_DRIVERS
|
||||||
|
@ -232,7 +283,13 @@
|
||||||
#define INVERT_E_STEP_PIN false
|
#define INVERT_E_STEP_PIN false
|
||||||
|
|
||||||
// Default stepper release if idle. Set to 0 to deactivate.
|
// Default stepper release if idle. Set to 0 to deactivate.
|
||||||
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
|
||||||
|
// Time can be set by M18 and M84.
|
||||||
|
#define DEFAULT_STEPPER_DEACTIVE_TIME 120
|
||||||
|
#define DISABLE_INACTIVE_X true
|
||||||
|
#define DISABLE_INACTIVE_Y true
|
||||||
|
#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished.
|
||||||
|
#define DISABLE_INACTIVE_E true
|
||||||
|
|
||||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
||||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
||||||
|
@ -268,6 +325,9 @@
|
||||||
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
||||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||||
|
|
||||||
|
// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
|
||||||
|
//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
|
||||||
|
|
||||||
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
||||||
|
@ -344,13 +404,13 @@
|
||||||
// @section more
|
// @section more
|
||||||
|
|
||||||
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
||||||
//#define USE_WATCHDOG
|
#define USE_WATCHDOG
|
||||||
|
|
||||||
#if ENABLED(USE_WATCHDOG)
|
#if ENABLED(USE_WATCHDOG)
|
||||||
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
||||||
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
||||||
// 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.
|
// 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.
|
||||||
//#define WATCHDOG_RESET_MANUAL
|
//#define WATCHDOG_RESET_MANUAL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
@ -361,7 +421,7 @@
|
||||||
//#define BABYSTEPPING
|
//#define BABYSTEPPING
|
||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
||||||
//not implemented for CoreXY and deltabots!
|
//not implemented for deltabots!
|
||||||
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
||||||
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
||||||
#endif
|
#endif
|
||||||
|
@ -380,7 +440,6 @@
|
||||||
#if ENABLED(ADVANCE)
|
#if ENABLED(ADVANCE)
|
||||||
#define EXTRUDER_ADVANCE_K .0
|
#define EXTRUDER_ADVANCE_K .0
|
||||||
#define D_FILAMENT 2.85
|
#define D_FILAMENT 2.85
|
||||||
#define STEPS_MM_E 836
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
@ -389,7 +448,7 @@
|
||||||
#define MM_PER_ARC_SEGMENT 1
|
#define MM_PER_ARC_SEGMENT 1
|
||||||
#define N_ARC_CORRECTION 25
|
#define N_ARC_CORRECTION 25
|
||||||
|
|
||||||
const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
|
@ -462,7 +521,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have TMC26X motor drivers.
|
* enable this section if you have TMC26X motor drivers.
|
||||||
* you need to import the TMC26XStepper library into the arduino IDE for this
|
* you need to import the TMC26XStepper library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section tmc
|
// @section tmc
|
||||||
|
@ -470,52 +529,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_TMCDRIVER
|
//#define HAVE_TMCDRIVER
|
||||||
#if ENABLED(HAVE_TMCDRIVER)
|
#if ENABLED(HAVE_TMCDRIVER)
|
||||||
|
|
||||||
//#define X_IS_TMC
|
//#define X_IS_TMC
|
||||||
#define X_MAX_CURRENT 1000 //in mA
|
#define X_MAX_CURRENT 1000 //in mA
|
||||||
#define X_SENSE_RESISTOR 91 //in mOhms
|
#define X_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define X2_IS_TMC
|
//#define X2_IS_TMC
|
||||||
#define X2_MAX_CURRENT 1000 //in mA
|
#define X2_MAX_CURRENT 1000 //in mA
|
||||||
#define X2_SENSE_RESISTOR 91 //in mOhms
|
#define X2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y_IS_TMC
|
//#define Y_IS_TMC
|
||||||
#define Y_MAX_CURRENT 1000 //in mA
|
#define Y_MAX_CURRENT 1000 //in mA
|
||||||
#define Y_SENSE_RESISTOR 91 //in mOhms
|
#define Y_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y2_IS_TMC
|
//#define Y2_IS_TMC
|
||||||
#define Y2_MAX_CURRENT 1000 //in mA
|
#define Y2_MAX_CURRENT 1000 //in mA
|
||||||
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z_IS_TMC
|
//#define Z_IS_TMC
|
||||||
#define Z_MAX_CURRENT 1000 //in mA
|
#define Z_MAX_CURRENT 1000 //in mA
|
||||||
#define Z_SENSE_RESISTOR 91 //in mOhms
|
#define Z_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z2_IS_TMC
|
//#define Z2_IS_TMC
|
||||||
#define Z2_MAX_CURRENT 1000 //in mA
|
#define Z2_MAX_CURRENT 1000 //in mA
|
||||||
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E0_IS_TMC
|
//#define E0_IS_TMC
|
||||||
#define E0_MAX_CURRENT 1000 //in mA
|
#define E0_MAX_CURRENT 1000 //in mA
|
||||||
#define E0_SENSE_RESISTOR 91 //in mOhms
|
#define E0_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E1_IS_TMC
|
//#define E1_IS_TMC
|
||||||
#define E1_MAX_CURRENT 1000 //in mA
|
#define E1_MAX_CURRENT 1000 //in mA
|
||||||
#define E1_SENSE_RESISTOR 91 //in mOhms
|
#define E1_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E2_IS_TMC
|
//#define E2_IS_TMC
|
||||||
#define E2_MAX_CURRENT 1000 //in mA
|
#define E2_MAX_CURRENT 1000 //in mA
|
||||||
#define E2_SENSE_RESISTOR 91 //in mOhms
|
#define E2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E3_IS_TMC
|
//#define E3_IS_TMC
|
||||||
#define E3_MAX_CURRENT 1000 //in mA
|
#define E3_MAX_CURRENT 1000 //in mA
|
||||||
#define E3_SENSE_RESISTOR 91 //in mOhms
|
#define E3_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
|
@ -524,7 +583,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have L6470 motor drivers.
|
* enable this section if you have L6470 motor drivers.
|
||||||
* you need to import the L6470 library into the arduino IDE for this
|
* you need to import the L6470 library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section l6470
|
// @section l6470
|
||||||
|
@ -532,66 +591,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_L6470DRIVER
|
//#define HAVE_L6470DRIVER
|
||||||
#if ENABLED(HAVE_L6470DRIVER)
|
#if ENABLED(HAVE_L6470DRIVER)
|
||||||
|
|
||||||
//#define X_IS_L6470
|
//#define X_IS_L6470
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define X2_IS_L6470
|
//#define X2_IS_L6470
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y_IS_L6470
|
//#define Y_IS_L6470
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y2_IS_L6470
|
//#define Y2_IS_L6470
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z_IS_L6470
|
//#define Z_IS_L6470
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z2_IS_L6470
|
//#define Z2_IS_L6470
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E0_IS_L6470
|
//#define E0_IS_L6470
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E1_IS_L6470
|
//#define E1_IS_L6470
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
|
||||||
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E2_IS_L6470
|
//#define E2_IS_L6470
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
|
||||||
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E3_IS_L6470
|
//#define E3_IS_L6470
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
|
||||||
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
|
|
@ -1,4 +1,26 @@
|
||||||
/*
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
* This file is a placeholder for a file which could be distributed in an archive
|
* This file is a placeholder for a file which could be distributed in an archive
|
||||||
* It takes the place of an automatically created "_Version.h" which is generated during the build process
|
* It takes the place of an automatically created "_Version.h" which is generated during the build process
|
||||||
*/
|
*/
|
||||||
|
@ -6,9 +28,9 @@
|
||||||
// #error "You must specify the following parameters related to your distribution"
|
// #error "You must specify the following parameters related to your distribution"
|
||||||
|
|
||||||
#if true
|
#if true
|
||||||
#define SHORT_BUILD_VERSION "1.1.0-RC3"
|
#define SHORT_BUILD_VERSION "1.1.0-RC5"
|
||||||
#define DETAILED_BUILD_VERSION "1.1.0-RC3 From Archive"
|
#define DETAILED_BUILD_VERSION "1.1.0-RC5 From Archive"
|
||||||
#define STRING_DISTRIBUTION_DATE "2015-12-01 12:00"
|
#define STRING_DISTRIBUTION_DATE "2016-04-01 12:00"
|
||||||
// It might also be appropriate to define a location where additional information can be found
|
// It might also be appropriate to define a location where additional information can be found
|
||||||
#define SOURCE_CODE_URL "http:// ..."
|
// #define SOURCE_CODE_URL "http:// ..."
|
||||||
#endif
|
#endif
|
|
@ -1,26 +1,45 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* M100 Free Memory Watcher
|
||||||
|
*
|
||||||
|
* This code watches the free memory block between the bottom of the heap and the top of the stack.
|
||||||
|
* This memory block is initialized and watched via the M100 command.
|
||||||
|
*
|
||||||
|
* M100 I Initializes the free memory block and prints vitals statistics about the area
|
||||||
|
* M100 F Identifies how much of the free memory block remains free and unused. It also
|
||||||
|
* detects and reports any corruption within the free memory block that may have
|
||||||
|
* happened due to errant firmware.
|
||||||
|
* M100 D Does a hex display of the free memory block along with a flag for any errant
|
||||||
|
* data that does not match the expected value.
|
||||||
|
* M100 C x Corrupts x locations within the free memory block. This is useful to check the
|
||||||
|
* correctness of the M100 F and M100 D commands.
|
||||||
|
*
|
||||||
|
* Initial version by Roxy-3DPrintBoard
|
||||||
|
*/
|
||||||
#define M100_FREE_MEMORY_DUMPER // Comment out to remove Dump sub-command
|
#define M100_FREE_MEMORY_DUMPER // Comment out to remove Dump sub-command
|
||||||
#define M100_FREE_MEMORY_CORRUPTOR // Comment out to remove Corrupt sub-command
|
#define M100_FREE_MEMORY_CORRUPTOR // Comment out to remove Corrupt sub-command
|
||||||
|
|
||||||
|
|
||||||
// M100 Free Memory Watcher
|
|
||||||
//
|
|
||||||
// This code watches the free memory block between the bottom of the heap and the top of the stack.
|
|
||||||
// This memory block is initialized and watched via the M100 command.
|
|
||||||
//
|
|
||||||
// M100 I Initializes the free memory block and prints vitals statistics about the area
|
|
||||||
// M100 F Identifies how much of the free memory block remains free and unused. It also
|
|
||||||
// detects and reports any corruption within the free memory block that may have
|
|
||||||
// happened due to errant firmware.
|
|
||||||
// M100 D Does a hex display of the free memory block along with a flag for any errant
|
|
||||||
// data that does not match the expected value.
|
|
||||||
// M100 C x Corrupts x locations within the free memory block. This is useful to check the
|
|
||||||
// correctness of the M100 F and M100 D commands.
|
|
||||||
//
|
|
||||||
// Initial version by Roxy-3DPrintBoard
|
|
||||||
//
|
|
||||||
//
|
|
||||||
|
|
||||||
|
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
|
|
||||||
#if ENABLED(M100_FREE_MEMORY_WATCHER)
|
#if ENABLED(M100_FREE_MEMORY_WATCHER)
|
||||||
|
@ -118,8 +137,10 @@ void gcode_M100() {
|
||||||
// other vital statistics that define the memory pool.
|
// other vital statistics that define the memory pool.
|
||||||
//
|
//
|
||||||
if (code_seen('F')) {
|
if (code_seen('F')) {
|
||||||
int max_addr = (int) __brkval;
|
#if 0
|
||||||
int max_cnt = 0;
|
int max_addr = (int) __brkval;
|
||||||
|
int max_cnt = 0;
|
||||||
|
#endif
|
||||||
int block_cnt = 0;
|
int block_cnt = 0;
|
||||||
ptr = (unsigned char*) __brkval;
|
ptr = (unsigned char*) __brkval;
|
||||||
sp = top_of_stack();
|
sp = top_of_stack();
|
||||||
|
@ -136,10 +157,12 @@ void gcode_M100() {
|
||||||
i += j;
|
i += j;
|
||||||
block_cnt++;
|
block_cnt++;
|
||||||
}
|
}
|
||||||
if (j > max_cnt) { // We don't do anything with this information yet
|
#if 0
|
||||||
max_cnt = j; // but we do know where the biggest free memory block is.
|
if (j > max_cnt) { // We don't do anything with this information yet
|
||||||
max_addr = (int) ptr + i;
|
max_cnt = j; // but we do know where the biggest free memory block is.
|
||||||
}
|
max_addr = (int) ptr + i;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (block_cnt > 1)
|
if (block_cnt > 1)
|
||||||
|
|
|
@ -12,14 +12,14 @@
|
||||||
#
|
#
|
||||||
# Detailed instructions for using the makefile:
|
# Detailed instructions for using the makefile:
|
||||||
#
|
#
|
||||||
# 1. Modify the line containg "ARDUINO_INSTALL_DIR" to point to the directory that
|
# 1. Modify the line containing "ARDUINO_INSTALL_DIR" to point to the directory that
|
||||||
# contains the Arduino installation (for example, under Mac OS X, this
|
# contains the Arduino installation (for example, under Mac OS X, this
|
||||||
# might be /Applications/Arduino.app/Contents/Resources/Java).
|
# might be /Applications/Arduino.app/Contents/Resources/Java).
|
||||||
#
|
#
|
||||||
# 2. Modify the line containing "UPLOAD_PORT" to refer to the filename
|
# 2. Modify the line containing "UPLOAD_PORT" to refer to the filename
|
||||||
# representing the USB or serial connection to your Arduino board
|
# representing the USB or serial connection to your Arduino board
|
||||||
# (e.g. UPLOAD_PORT = /dev/tty.USB0). If the exact name of this file
|
# (e.g. UPLOAD_PORT = /dev/tty.USB0). If the exact name of this file
|
||||||
# changes, you can use * as a wildcard (e.g. UPLOAD_PORT = /dev/tty.usb*).
|
# changes, you can use * as a wild card (e.g. UPLOAD_PORT = /dev/tty.usb*).
|
||||||
#
|
#
|
||||||
# 3. Set the line containing "MCU" to match your board's processor.
|
# 3. Set the line containing "MCU" to match your board's processor.
|
||||||
# Older one's are atmega8 based, newer ones like Arduino Mini, Bluetooth
|
# Older one's are atmega8 based, newer ones like Arduino Mini, Bluetooth
|
||||||
|
@ -163,6 +163,9 @@ MCU ?= at90usb1286
|
||||||
else ifeq ($(HARDWARE_MOTHERBOARD),81)
|
else ifeq ($(HARDWARE_MOTHERBOARD),81)
|
||||||
HARDWARE_VARIANT ?= Teensy
|
HARDWARE_VARIANT ?= Teensy
|
||||||
MCU ?= at90usb1286
|
MCU ?= at90usb1286
|
||||||
|
else ifeq ($(HARDWARE_MOTHERBOARD),811)
|
||||||
|
HARDWARE_VARIANT ?= Teensy
|
||||||
|
MCU ?= at90usb1286
|
||||||
else ifeq ($(HARDWARE_MOTHERBOARD),82)
|
else ifeq ($(HARDWARE_MOTHERBOARD),82)
|
||||||
HARDWARE_VARIANT ?= Teensy
|
HARDWARE_VARIANT ?= Teensy
|
||||||
MCU ?= at90usb646
|
MCU ?= at90usb646
|
||||||
|
@ -218,7 +221,7 @@ endif
|
||||||
# Set to 16Mhz if not yet set.
|
# Set to 16Mhz if not yet set.
|
||||||
F_CPU ?= 16000000
|
F_CPU ?= 16000000
|
||||||
|
|
||||||
# Arduino containd the main source code for the Arduino
|
# Arduino contained the main source code for the Arduino
|
||||||
# Libraries, the "hardware variant" are for boards
|
# Libraries, the "hardware variant" are for boards
|
||||||
# that derives from that, and their source are present in
|
# that derives from that, and their source are present in
|
||||||
# the main Marlin source directory
|
# the main Marlin source directory
|
||||||
|
@ -287,7 +290,7 @@ CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \
|
||||||
SdFile.cpp SdVolume.cpp planner.cpp stepper.cpp \
|
SdFile.cpp SdVolume.cpp planner.cpp stepper.cpp \
|
||||||
temperature.cpp cardreader.cpp configuration_store.cpp \
|
temperature.cpp cardreader.cpp configuration_store.cpp \
|
||||||
watchdog.cpp SPI.cpp servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \
|
watchdog.cpp SPI.cpp servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \
|
||||||
vector_3.cpp qr_solve.cpp buzzer.cpp
|
dac_mcp4728.cpp vector_3.cpp qr_solve.cpp buzzer.cpp
|
||||||
ifeq ($(LIQUID_TWI2), 0)
|
ifeq ($(LIQUID_TWI2), 0)
|
||||||
CXXSRC += LiquidCrystal.cpp
|
CXXSRC += LiquidCrystal.cpp
|
||||||
else
|
else
|
||||||
|
@ -300,7 +303,7 @@ SRC += twi.c
|
||||||
CXXSRC += Wire.cpp
|
CXXSRC += Wire.cpp
|
||||||
endif
|
endif
|
||||||
|
|
||||||
#Check for Arduino 1.0.0 or higher and use the correct sourcefiles for that version
|
#Check for Arduino 1.0.0 or higher and use the correct source files for that version
|
||||||
ifeq ($(shell [ $(ARDUINO_VERSION) -ge 100 ] && echo true), true)
|
ifeq ($(shell [ $(ARDUINO_VERSION) -ge 100 ] && echo true), true)
|
||||||
CXXSRC += main.cpp
|
CXXSRC += main.cpp
|
||||||
else
|
else
|
||||||
|
@ -421,7 +424,7 @@ lss: $(BUILD_DIR)/$(TARGET).lss
|
||||||
sym: $(BUILD_DIR)/$(TARGET).sym
|
sym: $(BUILD_DIR)/$(TARGET).sym
|
||||||
|
|
||||||
# Program the device.
|
# Program the device.
|
||||||
# Do not try to reset an arduino if it's not one
|
# Do not try to reset an Arduino if it's not one
|
||||||
upload: $(BUILD_DIR)/$(TARGET).hex
|
upload: $(BUILD_DIR)/$(TARGET).hex
|
||||||
ifeq (${AVRDUDE_PROGRAMMER}, arduino)
|
ifeq (${AVRDUDE_PROGRAMMER}, arduino)
|
||||||
stty hup < $(UPLOAD_PORT); true
|
stty hup < $(UPLOAD_PORT); true
|
||||||
|
|
|
@ -1,12 +1,30 @@
|
||||||
// Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
|
/**
|
||||||
// License: GPL
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef MARLIN_H
|
#ifndef MARLIN_H
|
||||||
#define MARLIN_H
|
#define MARLIN_H
|
||||||
|
|
||||||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||||
/**
|
/**
|
||||||
* Compiler warning on unused varable.
|
* Compiler warning on unused variable.
|
||||||
*/
|
*/
|
||||||
#define UNUSED(x) (void) (x)
|
#define UNUSED(x) (void) (x)
|
||||||
|
|
||||||
|
@ -45,13 +63,6 @@ typedef unsigned long millis_t;
|
||||||
|
|
||||||
#include "MarlinSerial.h"
|
#include "MarlinSerial.h"
|
||||||
|
|
||||||
#ifndef cbi
|
|
||||||
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
|
|
||||||
#endif
|
|
||||||
#ifndef sbi
|
|
||||||
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include "WString.h"
|
#include "WString.h"
|
||||||
|
|
||||||
#ifdef USBCON
|
#ifdef USBCON
|
||||||
|
@ -98,7 +109,6 @@ void serial_echopair_P(const char* s_P, float v);
|
||||||
void serial_echopair_P(const char* s_P, double v);
|
void serial_echopair_P(const char* s_P, double v);
|
||||||
void serial_echopair_P(const char* s_P, unsigned long v);
|
void serial_echopair_P(const char* s_P, unsigned long v);
|
||||||
|
|
||||||
|
|
||||||
// Things to write to serial from Program memory. Saves 400 to 2k of RAM.
|
// Things to write to serial from Program memory. Saves 400 to 2k of RAM.
|
||||||
FORCE_INLINE void serialprintPGM(const char* str) {
|
FORCE_INLINE void serialprintPGM(const char* str) {
|
||||||
char ch;
|
char ch;
|
||||||
|
@ -108,9 +118,11 @@ FORCE_INLINE void serialprintPGM(const char* str) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void get_command();
|
void idle(
|
||||||
|
#if ENABLED(FILAMENTCHANGEENABLE)
|
||||||
void idle(); // the standard idle routine calls manage_inactivity(false)
|
bool no_stepper_sleep=false // pass true to keep steppers from disabling on timeout
|
||||||
|
#endif
|
||||||
|
);
|
||||||
|
|
||||||
void manage_inactivity(bool ignore_stepper_queue = false);
|
void manage_inactivity(bool ignore_stepper_queue = false);
|
||||||
|
|
||||||
|
@ -217,21 +229,24 @@ void Stop();
|
||||||
* Debug flags - not yet widely applied
|
* Debug flags - not yet widely applied
|
||||||
*/
|
*/
|
||||||
enum DebugFlags {
|
enum DebugFlags {
|
||||||
DEBUG_ECHO = BIT(0),
|
DEBUG_NONE = 0,
|
||||||
DEBUG_INFO = BIT(1),
|
DEBUG_ECHO = _BV(0),
|
||||||
DEBUG_ERRORS = BIT(2),
|
DEBUG_INFO = _BV(1),
|
||||||
DEBUG_DRYRUN = BIT(3),
|
DEBUG_ERRORS = _BV(2),
|
||||||
DEBUG_COMMUNICATION = BIT(4),
|
DEBUG_DRYRUN = _BV(3),
|
||||||
DEBUG_LEVELING = BIT(5)
|
DEBUG_COMMUNICATION = _BV(4),
|
||||||
|
DEBUG_LEVELING = _BV(5)
|
||||||
};
|
};
|
||||||
extern uint8_t marlin_debug_flags;
|
extern uint8_t marlin_debug_flags;
|
||||||
|
#define DEBUGGING(F) (marlin_debug_flags & (DEBUG_## F))
|
||||||
|
|
||||||
extern bool Running;
|
extern bool Running;
|
||||||
inline bool IsRunning() { return Running; }
|
inline bool IsRunning() { return Running; }
|
||||||
inline bool IsStopped() { return !Running; }
|
inline bool IsStopped() { return !Running; }
|
||||||
|
|
||||||
bool enqueuecommand(const char* cmd); //put a single ASCII command at the end of the current buffer or return false when it is full
|
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
|
||||||
void enqueuecommands_P(const char* cmd); //put one or many ASCII commands at the end of the current buffer, read from flash
|
void enqueue_and_echo_command_now(const char* cmd); // enqueue now, only return when the command has been enqueued
|
||||||
|
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
|
||||||
|
|
||||||
void prepare_arc_move(char isclockwise);
|
void prepare_arc_move(char isclockwise);
|
||||||
void clamp_to_software_endstops(float target[3]);
|
void clamp_to_software_endstops(float target[3]);
|
||||||
|
@ -259,11 +274,9 @@ extern float home_offset[3]; // axis[n].home_offset
|
||||||
extern float min_pos[3]; // axis[n].min_pos
|
extern float min_pos[3]; // axis[n].min_pos
|
||||||
extern float max_pos[3]; // axis[n].max_pos
|
extern float max_pos[3]; // axis[n].max_pos
|
||||||
extern bool axis_known_position[3]; // axis[n].is_known
|
extern bool axis_known_position[3]; // axis[n].is_known
|
||||||
|
extern bool axis_homed[3]; // axis[n].is_homed
|
||||||
|
|
||||||
#if ENABLED(DELTA)
|
#if ENABLED(DELTA)
|
||||||
extern float delta[3];
|
|
||||||
extern float endstop_adj[3]; // axis[n].endstop_adj
|
|
||||||
extern float delta_radius;
|
|
||||||
#ifndef DELTA_RADIUS_TRIM_TOWER_1
|
#ifndef DELTA_RADIUS_TRIM_TOWER_1
|
||||||
#define DELTA_RADIUS_TRIM_TOWER_1 0.0
|
#define DELTA_RADIUS_TRIM_TOWER_1 0.0
|
||||||
#endif
|
#endif
|
||||||
|
@ -273,7 +286,6 @@ extern bool axis_known_position[3]; // axis[n].is_known
|
||||||
#ifndef DELTA_RADIUS_TRIM_TOWER_3
|
#ifndef DELTA_RADIUS_TRIM_TOWER_3
|
||||||
#define DELTA_RADIUS_TRIM_TOWER_3 0.0
|
#define DELTA_RADIUS_TRIM_TOWER_3 0.0
|
||||||
#endif
|
#endif
|
||||||
extern float delta_diagonal_rod;
|
|
||||||
#ifndef DELTA_DIAGONAL_ROD_TRIM_TOWER_1
|
#ifndef DELTA_DIAGONAL_ROD_TRIM_TOWER_1
|
||||||
#define DELTA_DIAGONAL_ROD_TRIM_TOWER_1 0.0
|
#define DELTA_DIAGONAL_ROD_TRIM_TOWER_1 0.0
|
||||||
#endif
|
#endif
|
||||||
|
@ -283,7 +295,14 @@ extern bool axis_known_position[3]; // axis[n].is_known
|
||||||
#ifndef DELTA_DIAGONAL_ROD_TRIM_TOWER_3
|
#ifndef DELTA_DIAGONAL_ROD_TRIM_TOWER_3
|
||||||
#define DELTA_DIAGONAL_ROD_TRIM_TOWER_3 0.0
|
#define DELTA_DIAGONAL_ROD_TRIM_TOWER_3 0.0
|
||||||
#endif
|
#endif
|
||||||
|
extern float delta[3];
|
||||||
|
extern float endstop_adj[3]; // axis[n].endstop_adj
|
||||||
|
extern float delta_radius;
|
||||||
|
extern float delta_diagonal_rod;
|
||||||
extern float delta_segments_per_second;
|
extern float delta_segments_per_second;
|
||||||
|
extern float delta_diagonal_rod_trim_tower_1;
|
||||||
|
extern float delta_diagonal_rod_trim_tower_2;
|
||||||
|
extern float delta_diagonal_rod_trim_tower_3;
|
||||||
void calculate_delta(float cartesian[3]);
|
void calculate_delta(float cartesian[3]);
|
||||||
void recalc_delta_settings(float radius, float diagonal_rod);
|
void recalc_delta_settings(float radius, float diagonal_rod);
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
@ -308,22 +327,20 @@ extern bool axis_known_position[3]; // axis[n].is_known
|
||||||
extern float extrude_min_temp;
|
extern float extrude_min_temp;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
extern int fanSpeed;
|
#if FAN_COUNT > 0
|
||||||
|
extern int fanSpeeds[FAN_COUNT];
|
||||||
|
#endif
|
||||||
|
|
||||||
#if ENABLED(BARICUDA)
|
#if ENABLED(BARICUDA)
|
||||||
extern int ValvePressure;
|
extern int ValvePressure;
|
||||||
extern int EtoPPressure;
|
extern int EtoPPressure;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(FAN_SOFT_PWM)
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
extern unsigned char fanSpeedSoftPwm;
|
extern float filament_width_nominal; //holds the theoretical filament diameter i.e., 3.00 or 1.75
|
||||||
#endif
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_SENSOR)
|
|
||||||
extern float filament_width_nominal; //holds the theoretical filament diameter ie., 3.00 or 1.75
|
|
||||||
extern bool filament_sensor; //indicates that filament sensor readings should control extrusion
|
extern bool filament_sensor; //indicates that filament sensor readings should control extrusion
|
||||||
extern float filament_width_meas; //holds the filament diameter as accurately measured
|
extern float filament_width_meas; //holds the filament diameter as accurately measured
|
||||||
extern signed char measurement_delay[]; //ring buffer to delay measurement
|
extern int8_t measurement_delay[]; //ring buffer to delay measurement
|
||||||
extern int delay_index1, delay_index2; //ring buffer index. used by planner, temperature, and main code
|
extern int delay_index1, delay_index2; //ring buffer index. used by planner, temperature, and main code
|
||||||
extern float delay_dist; //delay distance counter
|
extern float delay_dist; //delay distance counter
|
||||||
extern int meas_delay_cm; //delay distance
|
extern int meas_delay_cm; //delay distance
|
||||||
|
@ -351,6 +368,15 @@ extern uint8_t active_extruder;
|
||||||
extern void digipot_i2c_init();
|
extern void digipot_i2c_init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_TEMP_HOTEND || HAS_TEMP_BED
|
||||||
|
void print_heaterstates();
|
||||||
|
#endif
|
||||||
|
|
||||||
extern void calculate_volumetric_multipliers();
|
extern void calculate_volumetric_multipliers();
|
||||||
|
|
||||||
|
// Print job timer related functions
|
||||||
|
millis_t print_job_timer();
|
||||||
|
bool print_job_start(millis_t t = 0);
|
||||||
|
bool print_job_stop(bool force = false);
|
||||||
|
|
||||||
#endif //MARLIN_H
|
#endif //MARLIN_H
|
||||||
|
|
|
@ -1,5 +1,6 @@
|
||||||
/**
|
/**
|
||||||
* Marlin Firmware
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* Based on Sprinter and grbl.
|
* Based on Sprinter and grbl.
|
||||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
@ -17,6 +18,9 @@
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
* About Marlin
|
* About Marlin
|
||||||
*
|
*
|
||||||
* This firmware is a mashup between Sprinter and grbl.
|
* This firmware is a mashup between Sprinter and grbl.
|
||||||
|
@ -40,8 +44,12 @@
|
||||||
#elif ENABLED(LCD_I2C_TYPE_MCP23017) || ENABLED(LCD_I2C_TYPE_MCP23008)
|
#elif ENABLED(LCD_I2C_TYPE_MCP23017) || ENABLED(LCD_I2C_TYPE_MCP23008)
|
||||||
#include <Wire.h>
|
#include <Wire.h>
|
||||||
#include <LiquidTWI2.h>
|
#include <LiquidTWI2.h>
|
||||||
|
#elif ENABLED(LCM1602)
|
||||||
|
#include <Wire.h>
|
||||||
|
#include <LCD.h>
|
||||||
|
#include <LiquidCrystal_I2C.h>
|
||||||
#elif ENABLED(DOGLCD)
|
#elif ENABLED(DOGLCD)
|
||||||
#include <U8glib.h> // library for graphics LCD by Oli Kraus (https://code.google.com/p/u8glib/)
|
#include <U8glib.h> // library for graphics LCD by Oli Kraus (https://github.com/olikraus/U8glib_Arduino)
|
||||||
#else
|
#else
|
||||||
#include <LiquidCrystal.h> // library for character LCD
|
#include <LiquidCrystal.h> // library for character LCD
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -1,21 +1,29 @@
|
||||||
/*
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
HardwareSerial.cpp - Hardware serial library for Wiring
|
HardwareSerial.cpp - Hardware serial library for Wiring
|
||||||
Copyright (c) 2006 Nicholas Zambetti. All right reserved.
|
Copyright (c) 2006 Nicholas Zambetti. All right reserved.
|
||||||
|
|
||||||
This library is free software; you can redistribute it and/or
|
|
||||||
modify it under the terms of the GNU Lesser General Public
|
|
||||||
License as published by the Free Software Foundation; either
|
|
||||||
version 2.1 of the License, or (at your option) any later version.
|
|
||||||
|
|
||||||
This library is distributed in the hope that it will be useful,
|
|
||||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
|
||||||
Lesser General Public License for more details.
|
|
||||||
|
|
||||||
You should have received a copy of the GNU Lesser General Public
|
|
||||||
License along with this library; if not, write to the Free Software
|
|
||||||
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
|
||||||
|
|
||||||
Modified 23 November 2006 by David A. Mellis
|
Modified 23 November 2006 by David A. Mellis
|
||||||
Modified 28 September 2010 by Mark Sproul
|
Modified 28 September 2010 by Mark Sproul
|
||||||
*/
|
*/
|
||||||
|
@ -33,16 +41,19 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
FORCE_INLINE void store_char(unsigned char c) {
|
FORCE_INLINE void store_char(unsigned char c) {
|
||||||
int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE;
|
CRITICAL_SECTION_START;
|
||||||
|
uint8_t h = rx_buffer.head;
|
||||||
|
uint8_t i = (uint8_t)(h + 1) & (RX_BUFFER_SIZE - 1);
|
||||||
|
|
||||||
// if we should be storing the received character into the location
|
// if we should be storing the received character into the location
|
||||||
// just before the tail (meaning that the head would advance to the
|
// just before the tail (meaning that the head would advance to the
|
||||||
// current location of the tail), we're about to overflow the buffer
|
// current location of the tail), we're about to overflow the buffer
|
||||||
// and so we don't write the character or advance the head.
|
// and so we don't write the character or advance the head.
|
||||||
if (i != rx_buffer.tail) {
|
if (i != rx_buffer.tail) {
|
||||||
rx_buffer.buffer[rx_buffer.head] = c;
|
rx_buffer.buffer[h] = c;
|
||||||
rx_buffer.head = i;
|
rx_buffer.head = i;
|
||||||
}
|
}
|
||||||
|
CRITICAL_SECTION_END;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -76,7 +87,7 @@ void MarlinSerial::begin(long baud) {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (useU2X) {
|
if (useU2X) {
|
||||||
M_UCSRxA = BIT(M_U2Xx);
|
M_UCSRxA = _BV(M_U2Xx);
|
||||||
baud_setting = (F_CPU / 4 / baud - 1) / 2;
|
baud_setting = (F_CPU / 4 / baud - 1) / 2;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
@ -88,50 +99,56 @@ void MarlinSerial::begin(long baud) {
|
||||||
M_UBRRxH = baud_setting >> 8;
|
M_UBRRxH = baud_setting >> 8;
|
||||||
M_UBRRxL = baud_setting;
|
M_UBRRxL = baud_setting;
|
||||||
|
|
||||||
sbi(M_UCSRxB, M_RXENx);
|
SBI(M_UCSRxB, M_RXENx);
|
||||||
sbi(M_UCSRxB, M_TXENx);
|
SBI(M_UCSRxB, M_TXENx);
|
||||||
sbi(M_UCSRxB, M_RXCIEx);
|
SBI(M_UCSRxB, M_RXCIEx);
|
||||||
}
|
}
|
||||||
|
|
||||||
void MarlinSerial::end() {
|
void MarlinSerial::end() {
|
||||||
cbi(M_UCSRxB, M_RXENx);
|
CBI(M_UCSRxB, M_RXENx);
|
||||||
cbi(M_UCSRxB, M_TXENx);
|
CBI(M_UCSRxB, M_TXENx);
|
||||||
cbi(M_UCSRxB, M_RXCIEx);
|
CBI(M_UCSRxB, M_RXCIEx);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
int MarlinSerial::peek(void) {
|
int MarlinSerial::peek(void) {
|
||||||
if (rx_buffer.head == rx_buffer.tail) {
|
int v;
|
||||||
return -1;
|
CRITICAL_SECTION_START;
|
||||||
|
uint8_t t = rx_buffer.tail;
|
||||||
|
if (rx_buffer.head == t) {
|
||||||
|
v = -1;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
return rx_buffer.buffer[rx_buffer.tail];
|
v = rx_buffer.buffer[t];
|
||||||
}
|
}
|
||||||
|
CRITICAL_SECTION_END;
|
||||||
|
return v;
|
||||||
}
|
}
|
||||||
|
|
||||||
int MarlinSerial::read(void) {
|
int MarlinSerial::read(void) {
|
||||||
// if the head isn't ahead of the tail, we don't have any characters
|
int v;
|
||||||
if (rx_buffer.head == rx_buffer.tail) {
|
CRITICAL_SECTION_START;
|
||||||
return -1;
|
uint8_t t = rx_buffer.tail;
|
||||||
|
if (rx_buffer.head == t) {
|
||||||
|
v = -1;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
unsigned char c = rx_buffer.buffer[rx_buffer.tail];
|
v = rx_buffer.buffer[t];
|
||||||
rx_buffer.tail = (unsigned int)(rx_buffer.tail + 1) % RX_BUFFER_SIZE;
|
rx_buffer.tail = (uint8_t)(t + 1) & (RX_BUFFER_SIZE - 1);
|
||||||
return c;
|
|
||||||
}
|
}
|
||||||
|
CRITICAL_SECTION_END;
|
||||||
|
return v;
|
||||||
}
|
}
|
||||||
|
|
||||||
void MarlinSerial::flush() {
|
void MarlinSerial::flush() {
|
||||||
// don't reverse this or there may be problems if the RX interrupt
|
|
||||||
// occurs after reading the value of rx_buffer_head but before writing
|
|
||||||
// the value to rx_buffer_tail; the previous value of rx_buffer_head
|
|
||||||
// may be written to rx_buffer_tail, making it appear as if the buffer
|
|
||||||
// don't reverse this or there may be problems if the RX interrupt
|
// don't reverse this or there may be problems if the RX interrupt
|
||||||
// occurs after reading the value of rx_buffer_head but before writing
|
// occurs after reading the value of rx_buffer_head but before writing
|
||||||
// the value to rx_buffer_tail; the previous value of rx_buffer_head
|
// the value to rx_buffer_tail; the previous value of rx_buffer_head
|
||||||
// may be written to rx_buffer_tail, making it appear as if the buffer
|
// may be written to rx_buffer_tail, making it appear as if the buffer
|
||||||
// were full, not empty.
|
// were full, not empty.
|
||||||
rx_buffer.head = rx_buffer.tail;
|
CRITICAL_SECTION_START;
|
||||||
|
rx_buffer.head = rx_buffer.tail;
|
||||||
|
CRITICAL_SECTION_END;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -1,21 +1,29 @@
|
||||||
/*
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
HardwareSerial.h - Hardware serial library for Wiring
|
HardwareSerial.h - Hardware serial library for Wiring
|
||||||
Copyright (c) 2006 Nicholas Zambetti. All right reserved.
|
Copyright (c) 2006 Nicholas Zambetti. All right reserved.
|
||||||
|
|
||||||
This library is free software; you can redistribute it and/or
|
|
||||||
modify it under the terms of the GNU Lesser General Public
|
|
||||||
License as published by the Free Software Foundation; either
|
|
||||||
version 2.1 of the License, or (at your option) any later version.
|
|
||||||
|
|
||||||
This library is distributed in the hope that it will be useful,
|
|
||||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
|
|
||||||
Lesser General Public License for more details.
|
|
||||||
|
|
||||||
You should have received a copy of the GNU Lesser General Public
|
|
||||||
License along with this library; if not, write to the Free Software
|
|
||||||
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
|
|
||||||
|
|
||||||
Modified 28 September 2010 by Mark Sproul
|
Modified 28 September 2010 by Mark Sproul
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
@ -23,6 +31,12 @@
|
||||||
#define MarlinSerial_h
|
#define MarlinSerial_h
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
|
|
||||||
|
#ifndef CRITICAL_SECTION_START
|
||||||
|
#define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli();
|
||||||
|
#define CRITICAL_SECTION_END SREG = _sreg;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#ifndef SERIAL_PORT
|
#ifndef SERIAL_PORT
|
||||||
#define SERIAL_PORT 0
|
#define SERIAL_PORT 0
|
||||||
#endif
|
#endif
|
||||||
|
@ -69,13 +83,18 @@
|
||||||
// using a ring buffer (I think), in which rx_buffer_head is the index of the
|
// using a ring buffer (I think), in which rx_buffer_head is the index of the
|
||||||
// location to which to write the next incoming character and rx_buffer_tail
|
// location to which to write the next incoming character and rx_buffer_tail
|
||||||
// is the index of the location from which to read.
|
// is the index of the location from which to read.
|
||||||
#define RX_BUFFER_SIZE 128
|
// 256 is the max limit due to uint8_t head and tail. Use only powers of 2. (...,16,32,64,128,256)
|
||||||
|
#ifndef RX_BUFFER_SIZE
|
||||||
|
#define RX_BUFFER_SIZE 128
|
||||||
|
#endif
|
||||||
|
#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))
|
||||||
|
#error RX_BUFFER_SIZE has to be a power of 2 and >= 2
|
||||||
|
#endif
|
||||||
|
|
||||||
struct ring_buffer {
|
struct ring_buffer {
|
||||||
unsigned char buffer[RX_BUFFER_SIZE];
|
unsigned char buffer[RX_BUFFER_SIZE];
|
||||||
int head;
|
volatile uint8_t head;
|
||||||
int tail;
|
volatile uint8_t tail;
|
||||||
};
|
};
|
||||||
|
|
||||||
#if UART_PRESENT(SERIAL_PORT)
|
#if UART_PRESENT(SERIAL_PORT)
|
||||||
|
@ -92,8 +111,12 @@ class MarlinSerial { //: public Stream
|
||||||
int read(void);
|
int read(void);
|
||||||
void flush(void);
|
void flush(void);
|
||||||
|
|
||||||
FORCE_INLINE int available(void) {
|
FORCE_INLINE uint8_t available(void) {
|
||||||
return (unsigned int)(RX_BUFFER_SIZE + rx_buffer.head - rx_buffer.tail) % RX_BUFFER_SIZE;
|
CRITICAL_SECTION_START;
|
||||||
|
uint8_t h = rx_buffer.head;
|
||||||
|
uint8_t t = rx_buffer.tail;
|
||||||
|
CRITICAL_SECTION_END;
|
||||||
|
return (uint8_t)(RX_BUFFER_SIZE + h - t) & (RX_BUFFER_SIZE - 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
FORCE_INLINE void write(uint8_t c) {
|
FORCE_INLINE void write(uint8_t c) {
|
||||||
|
@ -105,16 +128,19 @@ class MarlinSerial { //: public Stream
|
||||||
FORCE_INLINE void checkRx(void) {
|
FORCE_INLINE void checkRx(void) {
|
||||||
if (TEST(M_UCSRxA, M_RXCx)) {
|
if (TEST(M_UCSRxA, M_RXCx)) {
|
||||||
unsigned char c = M_UDRx;
|
unsigned char c = M_UDRx;
|
||||||
int i = (unsigned int)(rx_buffer.head + 1) % RX_BUFFER_SIZE;
|
CRITICAL_SECTION_START;
|
||||||
|
uint8_t h = rx_buffer.head;
|
||||||
|
uint8_t i = (uint8_t)(h + 1) & (RX_BUFFER_SIZE - 1);
|
||||||
|
|
||||||
// if we should be storing the received character into the location
|
// if we should be storing the received character into the location
|
||||||
// just before the tail (meaning that the head would advance to the
|
// just before the tail (meaning that the head would advance to the
|
||||||
// current location of the tail), we're about to overflow the buffer
|
// current location of the tail), we're about to overflow the buffer
|
||||||
// and so we don't write the character or advance the head.
|
// and so we don't write the character or advance the head.
|
||||||
if (i != rx_buffer.tail) {
|
if (i != rx_buffer.tail) {
|
||||||
rx_buffer.buffer[rx_buffer.head] = c;
|
rx_buffer.buffer[h] = c;
|
||||||
rx_buffer.head = i;
|
rx_buffer.head = i;
|
||||||
}
|
}
|
||||||
|
CRITICAL_SECTION_END;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
File diff suppressed because it is too large
Load diff
|
@ -1,3 +1,25 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* SanityCheck.h
|
* SanityCheck.h
|
||||||
*
|
*
|
||||||
|
@ -6,6 +28,16 @@
|
||||||
#ifndef SANITYCHECK_H
|
#ifndef SANITYCHECK_H
|
||||||
#define SANITYCHECK_H
|
#define SANITYCHECK_H
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Due to the high number of issues related with old versions of Arduino IDE
|
||||||
|
* we are now warning our users to update their toolkits. In a future Marlin
|
||||||
|
* release we will stop supporting old IDE versions and will require user
|
||||||
|
* action to proceed with compilation in such environments.
|
||||||
|
*/
|
||||||
|
#if !defined(ARDUINO) || ARDUINO < 10500
|
||||||
|
#warning Versions of Arduino IDE prior to 1.5 are no longer supported, please update your toolkit.
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Dual Stepper Drivers
|
* Dual Stepper Drivers
|
||||||
*/
|
*/
|
||||||
|
@ -32,8 +64,8 @@
|
||||||
* Babystepping
|
* Babystepping
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
#if ENABLED(COREXY) && ENABLED(BABYSTEP_XY)
|
#if DISABLED(ULTRA_LCD)
|
||||||
#error BABYSTEPPING only implemented for Z axis on CoreXY.
|
#error BABYSTEPPING requires an LCD controller.
|
||||||
#endif
|
#endif
|
||||||
#if ENABLED(SCARA)
|
#if ENABLED(SCARA)
|
||||||
#error BABYSTEPPING is not implemented for SCARA yet.
|
#error BABYSTEPPING is not implemented for SCARA yet.
|
||||||
|
@ -109,6 +141,13 @@
|
||||||
#error You must enable either DISPLAY_CHARSET_HD44780_JAPAN or DISPLAY_CHARSET_HD44780_WESTERN or DISPLAY_CHARSET_HD44780_CYRILLIC for your LCD controller.
|
#error You must enable either DISPLAY_CHARSET_HD44780_JAPAN or DISPLAY_CHARSET_HD44780_WESTERN or DISPLAY_CHARSET_HD44780_CYRILLIC for your LCD controller.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Heating Options - PID vs Limit Switching
|
||||||
|
*/
|
||||||
|
#if ENABLED(PIDTEMPBED) && ENABLED(BED_LIMIT_SWITCHING)
|
||||||
|
#error To use BED_LIMIT_SWITCHING you must disable PIDTEMPBED.
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Mesh Bed Leveling
|
* Mesh Bed Leveling
|
||||||
*/
|
*/
|
||||||
|
@ -122,8 +161,38 @@
|
||||||
#if MESH_NUM_X_POINTS > 7 || MESH_NUM_Y_POINTS > 7
|
#if MESH_NUM_X_POINTS > 7 || MESH_NUM_Y_POINTS > 7
|
||||||
#error MESH_NUM_X_POINTS and MESH_NUM_Y_POINTS need to be less than 8.
|
#error MESH_NUM_X_POINTS and MESH_NUM_Y_POINTS need to be less than 8.
|
||||||
#endif
|
#endif
|
||||||
|
#elif ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#error MESH_BED_LEVELING is required for MANUAL_BED_LEVELING.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Probes
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* A probe needs a pin
|
||||||
|
*/
|
||||||
|
#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))
|
||||||
|
#error A probe needs a pin! [Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN || HAS_Z_PROBE]
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#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))
|
||||||
|
#error A probe should not be connected to more then one pin! [Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN || HAS_Z_PROBE]
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Require one kind of probe
|
||||||
|
*/
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE) && !( ENABLED(FIX_MOUNTED_PROBE) || defined(Z_ENDSTOP_SERVO_NR) || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED))
|
||||||
|
#error For AUTO_BED_LEVELING_FEATURE define one kind of probe! {Servo | Z_PROBE_ALLEN_KEY | Z_PROBE_SLED | FIX_MOUNTED_PROBE]
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(Z_SAFE_HOMING)&& !( ENABLED(FIX_MOUNTED_PROBE) || defined(Z_ENDSTOP_SERVO_NR) || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED))
|
||||||
|
#error For Z_SAFE_HOMING define one kind of probe! {Servo | Z_PROBE_ALLEN_KEY | Z_PROBE_SLED | FIX_MOUNTED_PROBE]
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// To do: Fail with more then one probe defined
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Auto Bed Leveling
|
* Auto Bed Leveling
|
||||||
*/
|
*/
|
||||||
|
@ -167,7 +236,7 @@
|
||||||
* Check if Probe_Offset * Grid Points is greater than Probing Range
|
* Check if Probe_Offset * Grid Points is greater than Probing Range
|
||||||
*/
|
*/
|
||||||
#if ENABLED(AUTO_BED_LEVELING_GRID)
|
#if ENABLED(AUTO_BED_LEVELING_GRID)
|
||||||
#ifndef DELTA_PROBABLE_RADIUS
|
#ifndef DELTA_PROBEABLE_RADIUS
|
||||||
// Be sure points are in the right order
|
// Be sure points are in the right order
|
||||||
#if LEFT_PROBE_BED_POSITION > RIGHT_PROBE_BED_POSITION
|
#if LEFT_PROBE_BED_POSITION > RIGHT_PROBE_BED_POSITION
|
||||||
#error LEFT_PROBE_BED_POSITION must be less than RIGHT_PROBE_BED_POSITION.
|
#error LEFT_PROBE_BED_POSITION must be less than RIGHT_PROBE_BED_POSITION.
|
||||||
|
@ -206,6 +275,14 @@
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*/
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR) && !HAS_FILAMENT_WIDTH_SENSOR
|
||||||
|
#error FILAMENT_WIDTH_SENSOR requires a FILWIDTH_PIN to be defined.
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* ULTIPANEL encoder
|
* ULTIPANEL encoder
|
||||||
*/
|
*/
|
||||||
|
@ -228,10 +305,6 @@
|
||||||
#error You cannot use Z_PROBE_SLED with DELTA.
|
#error You cannot use Z_PROBE_SLED with DELTA.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
|
|
||||||
#error Z_MIN_PROBE_REPEATABILITY_TEST is not supported with DELTA yet.
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -261,47 +334,63 @@
|
||||||
/**
|
/**
|
||||||
* Make sure auto fan pins don't conflict with the fan pin
|
* Make sure auto fan pins don't conflict with the fan pin
|
||||||
*/
|
*/
|
||||||
#if HAS_AUTO_FAN && HAS_FAN
|
#if HAS_AUTO_FAN
|
||||||
#if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN
|
#if HAS_FAN0
|
||||||
#error You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN.
|
#if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN
|
||||||
#elif EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN
|
#error You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN.
|
||||||
#error You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN.
|
#elif EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN
|
||||||
#elif EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN
|
#error You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN.
|
||||||
#error You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN.
|
#elif EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN
|
||||||
#elif EXTRUDER_3_AUTO_FAN_PIN == FAN_PIN
|
#error You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN.
|
||||||
#error You cannot set EXTRUDER_3_AUTO_FAN_PIN equal to FAN_PIN.
|
#elif EXTRUDER_3_AUTO_FAN_PIN == FAN_PIN
|
||||||
|
#error You cannot set EXTRUDER_3_AUTO_FAN_PIN equal to FAN_PIN.
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_FAN && CONTROLLERFAN_PIN == FAN_PIN
|
#if HAS_FAN0 && CONTROLLERFAN_PIN == FAN_PIN
|
||||||
#error You cannot set CONTROLLERFAN_PIN equal to FAN_PIN.
|
#error You cannot set CONTROLLERFAN_PIN equal to FAN_PIN.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_CONTROLLERFAN
|
||||||
|
#if EXTRUDER_0_AUTO_FAN_PIN == CONTROLLERFAN_PIN
|
||||||
|
#error You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN.
|
||||||
|
#elif EXTRUDER_1_AUTO_FAN_PIN == CONTROLLERFAN_PIN
|
||||||
|
#error You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN.
|
||||||
|
#elif EXTRUDER_2_AUTO_FAN_PIN == CONTROLLERFAN_PIN
|
||||||
|
#error You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN.
|
||||||
|
#elif EXTRUDER_3_AUTO_FAN_PIN == CONTROLLERFAN_PIN
|
||||||
|
#error You cannot set EXTRUDER_3_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN.
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Test Heater, Temp Sensor, and Extruder Pins; Sensor Type must also be set.
|
* Test Heater, Temp Sensor, and Extruder Pins; Sensor Type must also be set.
|
||||||
*/
|
*/
|
||||||
#if EXTRUDERS > 3
|
#if EXTRUDERS > 3
|
||||||
#if !HAS_HEATER_3
|
#if TEMP_SENSOR_3 == 0
|
||||||
|
#error TEMP_SENSOR_3 is required with 4 EXTRUDERS.
|
||||||
|
#elif !HAS_HEATER_3
|
||||||
#error HEATER_3_PIN not defined for this board.
|
#error HEATER_3_PIN not defined for this board.
|
||||||
#elif !PIN_EXISTS(TEMP_3)
|
#elif !PIN_EXISTS(TEMP_3)
|
||||||
#error TEMP_3_PIN not defined for this board.
|
#error TEMP_3_PIN not defined for this board.
|
||||||
#elif !PIN_EXISTS(E3_STEP) || !PIN_EXISTS(E3_DIR) || !PIN_EXISTS(E3_ENABLE)
|
#elif !PIN_EXISTS(E3_STEP) || !PIN_EXISTS(E3_DIR) || !PIN_EXISTS(E3_ENABLE)
|
||||||
#error E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board.
|
#error E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board.
|
||||||
#elif TEMP_SENSOR_3 == 0
|
|
||||||
#error TEMP_SENSOR_3 is required with 4 EXTRUDERS.
|
|
||||||
#endif
|
#endif
|
||||||
#elif EXTRUDERS > 2
|
#elif EXTRUDERS > 2
|
||||||
#if !HAS_HEATER_2
|
#if TEMP_SENSOR_2 == 0
|
||||||
|
#error TEMP_SENSOR_2 is required with 3 or more EXTRUDERS.
|
||||||
|
#elif !HAS_HEATER_2
|
||||||
#error HEATER_2_PIN not defined for this board.
|
#error HEATER_2_PIN not defined for this board.
|
||||||
#elif !PIN_EXISTS(TEMP_2)
|
#elif !PIN_EXISTS(TEMP_2)
|
||||||
#error TEMP_2_PIN not defined for this board.
|
#error TEMP_2_PIN not defined for this board.
|
||||||
#elif !PIN_EXISTS(E2_STEP) || !PIN_EXISTS(E2_DIR) || !PIN_EXISTS(E2_ENABLE)
|
#elif !PIN_EXISTS(E2_STEP) || !PIN_EXISTS(E2_DIR) || !PIN_EXISTS(E2_ENABLE)
|
||||||
#error E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board.
|
#error E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board.
|
||||||
#elif TEMP_SENSOR_2 == 0
|
|
||||||
#error TEMP_SENSOR_2 is required with 3 or more EXTRUDERS.
|
|
||||||
#endif
|
#endif
|
||||||
#elif EXTRUDERS > 1
|
#elif EXTRUDERS > 1
|
||||||
#if !PIN_EXISTS(TEMP_1)
|
#if TEMP_SENSOR_1 == 0
|
||||||
|
#error TEMP_SENSOR_1 is required with 2 or more EXTRUDERS.
|
||||||
|
#elif !PIN_EXISTS(TEMP_1)
|
||||||
#error TEMP_1_PIN not defined for this board.
|
#error TEMP_1_PIN not defined for this board.
|
||||||
#elif !PIN_EXISTS(E1_STEP) || !PIN_EXISTS(E1_DIR) || !PIN_EXISTS(E1_ENABLE)
|
#elif !PIN_EXISTS(E1_STEP) || !PIN_EXISTS(E1_DIR) || !PIN_EXISTS(E1_ENABLE)
|
||||||
#error E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board.
|
#error E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board.
|
||||||
|
@ -314,12 +403,8 @@
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if TEMP_SENSOR_1 == 0
|
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) && TEMP_SENSOR_1 == 0
|
||||||
#if EXTRUDERS > 1
|
#error TEMP_SENSOR_1 is required with TEMP_SENSOR_1_AS_REDUNDANT.
|
||||||
#error TEMP_SENSOR_1 is required with 2 or more EXTRUDERS.
|
|
||||||
#elif ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
|
|
||||||
#error TEMP_SENSOR_1 is required with TEMP_SENSOR_1_AS_REDUNDANT.
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if !HAS_HEATER_0
|
#if !HAS_HEATER_0
|
||||||
|
@ -332,6 +417,19 @@
|
||||||
#error TEMP_SENSOR_0 is required.
|
#error TEMP_SENSOR_0 is required.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Endstops
|
||||||
|
*/
|
||||||
|
#if DISABLED(USE_XMIN_PLUG) && DISABLED(USE_XMAX_PLUG) && !(ENABLED(Z_DUAL_ENDSTOPS) && Z2_USE_ENDSTOP >= _XMAX_ && Z2_USE_ENDSTOP <= _XMIN_)
|
||||||
|
#error You must enable USE_XMIN_PLUG or USE_XMAX_PLUG
|
||||||
|
#elif DISABLED(USE_YMIN_PLUG) && DISABLED(USE_YMAX_PLUG) && !(ENABLED(Z_DUAL_ENDSTOPS) && Z2_USE_ENDSTOP >= _YMAX_ && Z2_USE_ENDSTOP <= _YMIN_)
|
||||||
|
#error You must enable USE_YMIN_PLUG or USE_YMAX_PLUG
|
||||||
|
#elif DISABLED(USE_ZMIN_PLUG) && DISABLED(USE_ZMAX_PLUG) && !(ENABLED(Z_DUAL_ENDSTOPS) && Z2_USE_ENDSTOP >= _ZMAX_ && Z2_USE_ENDSTOP <= _ZMIN_)
|
||||||
|
#error You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG
|
||||||
|
#elif ENABLED(Z_DUAL_ENDSTOPS) && !Z2_USE_ENDSTOP
|
||||||
|
#error You must set Z2_USE_ENDSTOP with Z_DUAL_ENDSTOPS
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Warnings for old configurations
|
* Warnings for old configurations
|
||||||
*/
|
*/
|
||||||
|
@ -358,9 +456,21 @@
|
||||||
#elif defined(CUSTOM_MENDEL_NAME)
|
#elif defined(CUSTOM_MENDEL_NAME)
|
||||||
#error CUSTOM_MENDEL_NAME is now CUSTOM_MACHINE_NAME. Please update your configuration.
|
#error CUSTOM_MENDEL_NAME is now CUSTOM_MACHINE_NAME. Please update your configuration.
|
||||||
#elif defined(HAS_AUTOMATIC_VERSIONING)
|
#elif defined(HAS_AUTOMATIC_VERSIONING)
|
||||||
#error HAS_AUTOMATIC_VERSIONING deprecated - use USE_AUTOMATIC_VERSIONING instead
|
#error HAS_AUTOMATIC_VERSIONING is now USE_AUTOMATIC_VERSIONING. Please update your configuration.
|
||||||
#elif defined(ENABLE_AUTO_BED_LEVELING)
|
#elif defined(ENABLE_AUTO_BED_LEVELING)
|
||||||
#error ENABLE_AUTO_BED_LEVELING deprecated - use AUTO_BED_LEVELING_FEATURE instead
|
#error ENABLE_AUTO_BED_LEVELING is now AUTO_BED_LEVELING_FEATURE. Please update your configuration.
|
||||||
|
#elif defined(SDSLOW)
|
||||||
|
#error SDSLOW deprecated. Set SPI_SPEED to SPI_HALF_SPEED instead.
|
||||||
|
#elif defined(SDEXTRASLOW)
|
||||||
|
#error SDEXTRASLOW deprecated. Set SPI_SPEED to SPI_QUARTER_SPEED instead.
|
||||||
|
#elif defined(Z_RAISE_BEFORE_HOMING)
|
||||||
|
#error Z_RAISE_BEFORE_HOMING is deprecated. Use MIN_Z_HEIGHT_FOR_HOMING instead.
|
||||||
|
#elif defined(FILAMENT_SENSOR)
|
||||||
|
#error FILAMENT_SENSOR is deprecated. Use FILAMENT_WIDTH_SENSOR instead.
|
||||||
|
#elif defined(DISABLE_MAX_ENDSTOPS) || defined(DISABLE_MIN_ENDSTOPS)
|
||||||
|
#error DISABLE_MAX_ENDSTOPS and DISABLE_MIN_ENDSTOPS deprecated. Use individual USE_*_PLUG options instead.
|
||||||
|
#elif ENABLED(Z_DUAL_ENDSTOPS) && !defined(Z2_USE_ENDSTOP)
|
||||||
|
#error Z_DUAL_ENDSTOPS settings are simplified. Just set Z2_USE_ENDSTOP to the endstop you want to repurpose for Z2
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif //SANITYCHECK_H
|
#endif //SANITYCHECK_H
|
||||||
|
|
|
@ -1,21 +1,30 @@
|
||||||
/* Arduino Sd2Card Library
|
/**
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
*
|
*
|
||||||
* This Library is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This Library is distributed in the hope that it will be useful,
|
* This program is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with the Arduino Sd2Card Library. If not, see
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
* <http://www.gnu.org/licenses/>.
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino Sd2Card Library
|
||||||
|
* Copyright (C) 2009 by William Greiman
|
||||||
|
*
|
||||||
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
|
|
||||||
|
@ -35,8 +44,8 @@
|
||||||
*/
|
*/
|
||||||
static void spiInit(uint8_t spiRate) {
|
static void spiInit(uint8_t spiRate) {
|
||||||
// See avr processor documentation
|
// See avr processor documentation
|
||||||
SPCR = BIT(SPE) | BIT(MSTR) | (spiRate >> 1);
|
SPCR = _BV(SPE) | _BV(MSTR) | (spiRate >> 1);
|
||||||
SPSR = spiRate & 1 || spiRate == 6 ? 0 : BIT(SPI2X);
|
SPSR = spiRate & 1 || spiRate == 6 ? 0 : _BV(SPI2X);
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
//------------------------------------------------------------------------------
|
||||||
/** SPI receive a byte */
|
/** SPI receive a byte */
|
||||||
|
@ -356,6 +365,7 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
|
||||||
#if DISABLED(SOFTWARE_SPI)
|
#if DISABLED(SOFTWARE_SPI)
|
||||||
return setSckRate(sckRateID);
|
return setSckRate(sckRateID);
|
||||||
#else // SOFTWARE_SPI
|
#else // SOFTWARE_SPI
|
||||||
|
UNUSED(sckRateID);
|
||||||
return true;
|
return true;
|
||||||
#endif // SOFTWARE_SPI
|
#endif // SOFTWARE_SPI
|
||||||
|
|
||||||
|
@ -498,9 +508,13 @@ bool Sd2Card::readData(uint8_t* dst, uint16_t count) {
|
||||||
spiRec();
|
spiRec();
|
||||||
#endif
|
#endif
|
||||||
chipSelectHigh();
|
chipSelectHigh();
|
||||||
|
// Send an additional dummy byte, required by Toshiba Flash Air SD Card
|
||||||
|
spiSend(0XFF);
|
||||||
return true;
|
return true;
|
||||||
fail:
|
fail:
|
||||||
chipSelectHigh();
|
chipSelectHigh();
|
||||||
|
// Send an additional dummy byte, required by Toshiba Flash Air SD Card
|
||||||
|
spiSend(0XFF);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
//------------------------------------------------------------------------------
|
||||||
|
|
|
@ -1,21 +1,30 @@
|
||||||
/* Arduino Sd2Card Library
|
/**
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
*
|
*
|
||||||
* This Library is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This Library is distributed in the hope that it will be useful,
|
* This program is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with the Arduino Sd2Card Library. If not, see
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
* <http://www.gnu.org/licenses/>.
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino Sd2Card Library
|
||||||
|
* Copyright (C) 2009 by William Greiman
|
||||||
|
*
|
||||||
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
|
|
|
@ -1,21 +1,30 @@
|
||||||
/* Arduino SdFat Library
|
/**
|
||||||
* Copyright (C) 2010 by William Greiman
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino SdFat Library
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
*
|
*
|
||||||
* This Library is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This Library is distributed in the hope that it will be useful,
|
* This program is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with the Arduino SdFat Library. If not, see
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
* <http://www.gnu.org/licenses/>.
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino SdFat Library
|
||||||
|
* Copyright (C) 2010 by William Greiman
|
||||||
|
*
|
||||||
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
// Warning this file was generated by a program.
|
// Warning this file was generated by a program.
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
|
@ -405,10 +414,10 @@ static inline __attribute__((always_inline))
|
||||||
void setPinMode(uint8_t pin, uint8_t mode) {
|
void setPinMode(uint8_t pin, uint8_t mode) {
|
||||||
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
|
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
|
||||||
if (mode) {
|
if (mode) {
|
||||||
*digitalPinMap[pin].ddr |= BIT(digitalPinMap[pin].bit);
|
SBI(*digitalPinMap[pin].ddr, digitalPinMap[pin].bit);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
*digitalPinMap[pin].ddr &= ~BIT(digitalPinMap[pin].bit);
|
CBI(*digitalPinMap[pin].ddr, digitalPinMap[pin].bit);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
@ -428,10 +437,10 @@ static inline __attribute__((always_inline))
|
||||||
void fastDigitalWrite(uint8_t pin, uint8_t value) {
|
void fastDigitalWrite(uint8_t pin, uint8_t value) {
|
||||||
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
|
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
|
||||||
if (value) {
|
if (value) {
|
||||||
*digitalPinMap[pin].port |= BIT(digitalPinMap[pin].bit);
|
SBI(*digitalPinMap[pin].port, digitalPinMap[pin].bit);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
*digitalPinMap[pin].port &= ~BIT(digitalPinMap[pin].bit);
|
CBI(*digitalPinMap[pin].port, digitalPinMap[pin].bit);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
|
|
@ -1,21 +1,30 @@
|
||||||
/* Arduino SdFat Library
|
/**
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino SdFat Library
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
*
|
*
|
||||||
* This Library is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This Library is distributed in the hope that it will be useful,
|
* This program is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with the Arduino SdFat Library. If not, see
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
* <http://www.gnu.org/licenses/>.
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino SdFat Library
|
||||||
|
* Copyright (C) 2009 by William Greiman
|
||||||
|
*
|
||||||
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
|
@ -291,7 +300,7 @@ bool SdBaseFile::getFilename(char* name) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
//------------------------------------------------------------------------------
|
||||||
void SdBaseFile::getpos(fpos_t* pos) {
|
void SdBaseFile::getpos(filepos_t* pos) {
|
||||||
pos->position = curPosition_;
|
pos->position = curPosition_;
|
||||||
pos->cluster = curCluster_;
|
pos->cluster = curCluster_;
|
||||||
}
|
}
|
||||||
|
@ -923,7 +932,7 @@ fail:
|
||||||
* \return The byte if no error and not at eof else -1;
|
* \return The byte if no error and not at eof else -1;
|
||||||
*/
|
*/
|
||||||
int SdBaseFile::peek() {
|
int SdBaseFile::peek() {
|
||||||
fpos_t pos;
|
filepos_t pos;
|
||||||
getpos(&pos);
|
getpos(&pos);
|
||||||
int c = read();
|
int c = read();
|
||||||
if (c >= 0) setpos(&pos);
|
if (c >= 0) setpos(&pos);
|
||||||
|
@ -1049,9 +1058,8 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) {
|
||||||
if (!isOpen() || !(flags_ & O_READ)) goto fail;
|
if (!isOpen() || !(flags_ & O_READ)) goto fail;
|
||||||
|
|
||||||
// max bytes left in file
|
// max bytes left in file
|
||||||
if (nbyte >= (fileSize_ - curPosition_)) {
|
NOMORE(nbyte, fileSize_ - curPosition_);
|
||||||
nbyte = fileSize_ - curPosition_;
|
|
||||||
}
|
|
||||||
// amount left to read
|
// amount left to read
|
||||||
toRead = nbyte;
|
toRead = nbyte;
|
||||||
while (toRead > 0) {
|
while (toRead > 0) {
|
||||||
|
@ -1077,7 +1085,7 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) {
|
||||||
uint16_t n = toRead;
|
uint16_t n = toRead;
|
||||||
|
|
||||||
// amount to be read from current block
|
// amount to be read from current block
|
||||||
if (n > (512 - offset)) n = 512 - offset;
|
NOMORE(n, 512 - offset);
|
||||||
|
|
||||||
// no buffering needed if n == 512
|
// no buffering needed if n == 512
|
||||||
if (n == 512 && block != vol_->cacheBlockNumber()) {
|
if (n == 512 && block != vol_->cacheBlockNumber()) {
|
||||||
|
@ -1135,7 +1143,7 @@ int8_t SdBaseFile::readDir(dir_t* dir, char* longFilename) {
|
||||||
// Sanity-check the VFAT entry. The first cluster is always set to zero. And the sequence number should be higher than 0
|
// Sanity-check the VFAT entry. The first cluster is always set to zero. And the sequence number should be higher than 0
|
||||||
if (VFAT->firstClusterLow == 0 && (VFAT->sequenceNumber & 0x1F) > 0 && (VFAT->sequenceNumber & 0x1F) <= MAX_VFAT_ENTRIES) {
|
if (VFAT->firstClusterLow == 0 && (VFAT->sequenceNumber & 0x1F) > 0 && (VFAT->sequenceNumber & 0x1F) <= MAX_VFAT_ENTRIES) {
|
||||||
// TODO: Store the filename checksum to verify if a none-long filename aware system modified the file table.
|
// TODO: Store the filename checksum to verify if a none-long filename aware system modified the file table.
|
||||||
n = ((VFAT->sequenceNumber & 0x1F) - 1) * FILENAME_LENGTH;
|
n = ((VFAT->sequenceNumber & 0x1F) - 1) * (FILENAME_LENGTH);
|
||||||
for (uint8_t i = 0; i < FILENAME_LENGTH; i++)
|
for (uint8_t i = 0; i < FILENAME_LENGTH; i++)
|
||||||
longFilename[n + i] = (i < 5) ? VFAT->name1[i] : (i < 11) ? VFAT->name2[i - 5] : VFAT->name3[i - 11];
|
longFilename[n + i] = (i < 5) ? VFAT->name1[i] : (i < 11) ? VFAT->name2[i - 5] : VFAT->name3[i - 11];
|
||||||
// If this VFAT entry is the last one, add a NUL terminator at the end of the string
|
// If this VFAT entry is the last one, add a NUL terminator at the end of the string
|
||||||
|
@ -1479,7 +1487,7 @@ fail:
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
//------------------------------------------------------------------------------
|
||||||
void SdBaseFile::setpos(fpos_t* pos) {
|
void SdBaseFile::setpos(filepos_t* pos) {
|
||||||
curPosition_ = pos->position;
|
curPosition_ = pos->position;
|
||||||
curCluster_ = pos->cluster;
|
curCluster_ = pos->cluster;
|
||||||
}
|
}
|
||||||
|
@ -1758,7 +1766,7 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) {
|
||||||
uint16_t n = 512 - blockOffset;
|
uint16_t n = 512 - blockOffset;
|
||||||
|
|
||||||
// lesser of space and amount to write
|
// lesser of space and amount to write
|
||||||
if (n > nToWrite) n = nToWrite;
|
NOMORE(n, nToWrite);
|
||||||
|
|
||||||
// block for data write
|
// block for data write
|
||||||
uint32_t block = vol_->clusterStartBlock(curCluster_) + blockOfCluster;
|
uint32_t block = vol_->clusterStartBlock(curCluster_) + blockOfCluster;
|
||||||
|
|
|
@ -1,21 +1,30 @@
|
||||||
/* Arduino SdFat Library
|
/**
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino SdFat Library
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
*
|
*
|
||||||
* This Library is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This Library is distributed in the hope that it will be useful,
|
* This program is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with the Arduino SdFat Library. If not, see
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
* <http://www.gnu.org/licenses/>.
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino SdFat Library
|
||||||
|
* Copyright (C) 2009 by William Greiman
|
||||||
|
*
|
||||||
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
@ -31,16 +40,16 @@
|
||||||
#include "SdVolume.h"
|
#include "SdVolume.h"
|
||||||
//------------------------------------------------------------------------------
|
//------------------------------------------------------------------------------
|
||||||
/**
|
/**
|
||||||
* \struct fpos_t
|
* \struct filepos_t
|
||||||
* \brief internal type for istream
|
* \brief internal type for istream
|
||||||
* do not use in user apps
|
* do not use in user apps
|
||||||
*/
|
*/
|
||||||
struct fpos_t {
|
struct filepos_t {
|
||||||
/** stream position */
|
/** stream position */
|
||||||
uint32_t position;
|
uint32_t position;
|
||||||
/** cluster for position */
|
/** cluster for position */
|
||||||
uint32_t cluster;
|
uint32_t cluster;
|
||||||
fpos_t() : position(0), cluster(0) {}
|
filepos_t() : position(0), cluster(0) {}
|
||||||
};
|
};
|
||||||
|
|
||||||
// use the gnu style oflag in open()
|
// use the gnu style oflag in open()
|
||||||
|
@ -196,11 +205,11 @@ class SdBaseFile {
|
||||||
/** get position for streams
|
/** get position for streams
|
||||||
* \param[out] pos struct to receive position
|
* \param[out] pos struct to receive position
|
||||||
*/
|
*/
|
||||||
void getpos(fpos_t* pos);
|
void getpos(filepos_t* pos);
|
||||||
/** set position for streams
|
/** set position for streams
|
||||||
* \param[out] pos struct with value for new position
|
* \param[out] pos struct with value for new position
|
||||||
*/
|
*/
|
||||||
void setpos(fpos_t* pos);
|
void setpos(filepos_t* pos);
|
||||||
//----------------------------------------------------------------------------
|
//----------------------------------------------------------------------------
|
||||||
bool close();
|
bool close();
|
||||||
bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
|
bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
|
||||||
|
|
|
@ -1,21 +1,30 @@
|
||||||
/* Arduino SdFat Library
|
/**
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino SdFat Library
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
*
|
*
|
||||||
* This Library is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This Library is distributed in the hope that it will be useful,
|
* This program is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with the Arduino SdFat Library. If not, see
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
* <http://www.gnu.org/licenses/>.
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino SdFat Library
|
||||||
|
* Copyright (C) 2009 by William Greiman
|
||||||
|
*
|
||||||
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
/**
|
/**
|
||||||
* \file
|
* \file
|
||||||
|
|
|
@ -1,21 +1,30 @@
|
||||||
/* Arduino SdFat Library
|
/**
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino SdFat Library
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
*
|
*
|
||||||
* This Library is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This Library is distributed in the hope that it will be useful,
|
* This program is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with the Arduino SdFat Library. If not, see
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
* <http://www.gnu.org/licenses/>.
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino SdFat Library
|
||||||
|
* Copyright (C) 2009 by William Greiman
|
||||||
|
*
|
||||||
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
@ -28,7 +37,7 @@
|
||||||
* \file
|
* \file
|
||||||
* \brief FAT file structures
|
* \brief FAT file structures
|
||||||
*/
|
*/
|
||||||
/*
|
/**
|
||||||
* mostly from Microsoft document fatgen103.doc
|
* mostly from Microsoft document fatgen103.doc
|
||||||
* http://www.microsoft.com/whdc/system/platform/firmware/fatgen.mspx
|
* http://www.microsoft.com/whdc/system/platform/firmware/fatgen.mspx
|
||||||
*/
|
*/
|
||||||
|
|
|
@ -1,21 +1,30 @@
|
||||||
/* Arduino SdFat Library
|
/**
|
||||||
* Copyright (C) 2008 by William Greiman
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino SdFat Library
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
*
|
*
|
||||||
* This Library is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This Library is distributed in the hope that it will be useful,
|
* This program is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with the Arduino SdFat Library. If not, see
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
* <http://www.gnu.org/licenses/>.
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino SdFat Library
|
||||||
|
* Copyright (C) 2008 by William Greiman
|
||||||
|
*
|
||||||
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
|
|
||||||
|
|
|
@ -1,21 +1,30 @@
|
||||||
/* Arduino SdFat Library
|
/**
|
||||||
* Copyright (C) 2008 by William Greiman
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino SdFat Library
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
*
|
*
|
||||||
* This Library is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This Library is distributed in the hope that it will be useful,
|
* This program is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with the Arduino SdFat Library. If not, see
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
* <http://www.gnu.org/licenses/>.
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino SdFat Library
|
||||||
|
* Copyright (C) 2008 by William Greiman
|
||||||
|
*
|
||||||
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
|
@ -1,21 +1,30 @@
|
||||||
/* Arduino SdFat Library
|
/**
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino SdFat Library
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
*
|
*
|
||||||
* This Library is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This Library is distributed in the hope that it will be useful,
|
* This program is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with the Arduino SdFat Library. If not, see
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
* <http://www.gnu.org/licenses/>.
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino SdFat Library
|
||||||
|
* Copyright (C) 2009 by William Greiman
|
||||||
|
*
|
||||||
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
|
|
||||||
|
|
|
@ -1,21 +1,30 @@
|
||||||
/* Arduino SdFat Library
|
/**
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino SdFat Library
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
*
|
*
|
||||||
* This Library is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This Library is distributed in the hope that it will be useful,
|
* This program is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with the Arduino SdFat Library. If not, see
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
* <http://www.gnu.org/licenses/>.
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino SdFat Library
|
||||||
|
* Copyright (C) 2009 by William Greiman
|
||||||
|
*
|
||||||
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
/**
|
/**
|
||||||
* \file
|
* \file
|
||||||
|
|
|
@ -1,21 +1,30 @@
|
||||||
/* Arduino Sd2Card Library
|
/**
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
*
|
*
|
||||||
* This Library is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This Library is distributed in the hope that it will be useful,
|
* This program is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with the Arduino Sd2Card Library. If not, see
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
* <http://www.gnu.org/licenses/>.
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino Sd2Card Library
|
||||||
|
* Copyright (C) 2009 by William Greiman
|
||||||
|
*
|
||||||
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
|
@ -1,21 +1,30 @@
|
||||||
/* Arduino SdFat Library
|
/**
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino SdFat Library
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
*
|
*
|
||||||
* This Library is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This Library is distributed in the hope that it will be useful,
|
* This program is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with the Arduino SdFat Library. If not, see
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
* <http://www.gnu.org/licenses/>.
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino SdFat Library
|
||||||
|
* Copyright (C) 2009 by William Greiman
|
||||||
|
*
|
||||||
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
@ -296,7 +305,7 @@ int32_t SdVolume::freeClusterCount() {
|
||||||
|
|
||||||
for (uint32_t lba = fatStartBlock_; todo; todo -= n, lba++) {
|
for (uint32_t lba = fatStartBlock_; todo; todo -= n, lba++) {
|
||||||
if (!cacheRawBlock(lba, CACHE_FOR_READ)) return -1;
|
if (!cacheRawBlock(lba, CACHE_FOR_READ)) return -1;
|
||||||
if (todo < n) n = todo;
|
NOMORE(n, todo);
|
||||||
if (fatType_ == 16) {
|
if (fatType_ == 16) {
|
||||||
for (uint16_t i = 0; i < n; i++) {
|
for (uint16_t i = 0; i < n; i++) {
|
||||||
if (cacheBuffer_.fat16[i] == 0) free++;
|
if (cacheBuffer_.fat16[i] == 0) free++;
|
||||||
|
@ -364,7 +373,7 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
|
||||||
blocksPerCluster_ = fbs->sectorsPerCluster;
|
blocksPerCluster_ = fbs->sectorsPerCluster;
|
||||||
// determine shift that is same as multiply by blocksPerCluster_
|
// determine shift that is same as multiply by blocksPerCluster_
|
||||||
clusterSizeShift_ = 0;
|
clusterSizeShift_ = 0;
|
||||||
while (blocksPerCluster_ != BIT(clusterSizeShift_)) {
|
while (blocksPerCluster_ != _BV(clusterSizeShift_)) {
|
||||||
// error if not power of 2
|
// error if not power of 2
|
||||||
if (clusterSizeShift_++ > 7) goto fail;
|
if (clusterSizeShift_++ > 7) goto fail;
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,21 +1,30 @@
|
||||||
/* Arduino SdFat Library
|
/**
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino SdFat Library
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
*
|
*
|
||||||
* This Library is free software: you can redistribute it and/or modify
|
* This program is free software: you can redistribute it and/or modify
|
||||||
* it under the terms of the GNU General Public License as published by
|
* it under the terms of the GNU General Public License as published by
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
* (at your option) any later version.
|
* (at your option) any later version.
|
||||||
*
|
*
|
||||||
* This Library is distributed in the hope that it will be useful,
|
* This program is distributed in the hope that it will be useful,
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
* GNU General Public License for more details.
|
* GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with the Arduino SdFat Library. If not, see
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
* <http://www.gnu.org/licenses/>.
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino SdFat Library
|
||||||
|
* Copyright (C) 2009 by William Greiman
|
||||||
|
*
|
||||||
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
|
@ -1,7 +1,30 @@
|
||||||
/*
|
/**
|
||||||
blinkm.cpp - Library for controlling a BlinkM over i2c
|
* Marlin 3D Printer Firmware
|
||||||
Created by Tim Koster, August 21 2013.
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
*/
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* blinkm.cpp - Library for controlling a BlinkM over i2c
|
||||||
|
* Created by Tim Koster, August 21 2013.
|
||||||
|
*/
|
||||||
|
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
|
|
||||||
#if ENABLED(BLINKM)
|
#if ENABLED(BLINKM)
|
||||||
|
|
|
@ -1,6 +1,28 @@
|
||||||
/*
|
/**
|
||||||
blinkm.h
|
* Marlin 3D Printer Firmware
|
||||||
Library header file for BlinkM library
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* blinkm.h - Library for controlling a BlinkM over i2c
|
||||||
|
* Created by Tim Koster, August 21 2013.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "Arduino.h"
|
#include "Arduino.h"
|
||||||
|
|
|
@ -1,3 +1,25 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
#ifndef BOARDS_H
|
#ifndef BOARDS_H
|
||||||
#define BOARDS_H
|
#define BOARDS_H
|
||||||
|
|
||||||
|
@ -40,6 +62,7 @@
|
||||||
#define BOARD_TEENSYLU 8 // Teensylu
|
#define BOARD_TEENSYLU 8 // Teensylu
|
||||||
#define BOARD_RUMBA 80 // Rumba
|
#define BOARD_RUMBA 80 // Rumba
|
||||||
#define BOARD_PRINTRBOARD 81 // Printrboard (AT90USB1286)
|
#define BOARD_PRINTRBOARD 81 // Printrboard (AT90USB1286)
|
||||||
|
#define BOARD_PRINTRBOARD_REVF 811 // Printrboard Revision F (AT90USB1286)
|
||||||
#define BOARD_BRAINWAVE 82 // Brainwave (AT90USB646)
|
#define BOARD_BRAINWAVE 82 // Brainwave (AT90USB646)
|
||||||
#define BOARD_SAV_MKI 83 // SAV Mk-I (AT90USB1286)
|
#define BOARD_SAV_MKI 83 // SAV Mk-I (AT90USB1286)
|
||||||
#define BOARD_TEENSY2 84 // Teensy++2.0 (AT90USB1286) - CLI compile: DEFINES=AT90USBxx_TEENSYPP_ASSIGNMENTS HARDWARE_MOTHERBOARD=84 make
|
#define BOARD_TEENSY2 84 // Teensy++2.0 (AT90USB1286) - CLI compile: DEFINES=AT90USBxx_TEENSYPP_ASSIGNMENTS HARDWARE_MOTHERBOARD=84 make
|
||||||
|
@ -54,13 +77,17 @@
|
||||||
#define BOARD_OMCA 91 // Final OMCA board
|
#define BOARD_OMCA 91 // Final OMCA board
|
||||||
#define BOARD_RAMBO 301 // Rambo
|
#define BOARD_RAMBO 301 // Rambo
|
||||||
#define BOARD_MINIRAMBO 302 // Mini-Rambo
|
#define BOARD_MINIRAMBO 302 // Mini-Rambo
|
||||||
|
#define BOARD_AJ4P 303 // AJ4P
|
||||||
#define BOARD_MEGACONTROLLER 310 // Mega controller
|
#define BOARD_MEGACONTROLLER 310 // Mega controller
|
||||||
#define BOARD_ELEFU_3 21 // Elefu Ra Board (v3)
|
#define BOARD_ELEFU_3 21 // Elefu Ra Board (v3)
|
||||||
#define BOARD_5DPRINT 88 // 5DPrint D8 Driver Board
|
#define BOARD_5DPRINT 88 // 5DPrint D8 Driver Board
|
||||||
#define BOARD_LEAPFROG 999 // Leapfrog
|
#define BOARD_LEAPFROG 999 // Leapfrog
|
||||||
#define BOARD_MKS_BASE 40 // MKS BASE 1.0
|
#define BOARD_MKS_BASE 40 // MKS BASE 1.0
|
||||||
|
#define BOARD_MKS_13 47 // MKS v1.3 or 1.4 (maybe higher)
|
||||||
|
#define BOARD_SAINSMART_2IN1 49 // Sainsmart 2-in-1 board
|
||||||
#define BOARD_BAM_DICE 401 // 2PrintBeta BAM&DICE with STK drivers
|
#define BOARD_BAM_DICE 401 // 2PrintBeta BAM&DICE with STK drivers
|
||||||
#define BOARD_BAM_DICE_DUE 402 // 2PrintBeta BAM&DICE Due with STK drivers
|
#define BOARD_BAM_DICE_DUE 402 // 2PrintBeta BAM&DICE Due with STK drivers
|
||||||
|
#define BOARD_BQ_ZUM_MEGA_3D 503 // bq ZUM Mega 3D
|
||||||
|
|
||||||
#define BOARD_99 99 // This is in pins.h but...?
|
#define BOARD_99 99 // This is in pins.h but...?
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,25 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
#if HAS_BUZZER
|
#if HAS_BUZZER
|
||||||
#include "buzzer.h"
|
#include "buzzer.h"
|
||||||
|
|
|
@ -1,3 +1,25 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
#ifndef BUZZER_H
|
#ifndef BUZZER_H
|
||||||
#define BUZZER_H
|
#define BUZZER_H
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,25 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
#include "cardreader.h"
|
#include "cardreader.h"
|
||||||
#include "ultralcd.h"
|
#include "ultralcd.h"
|
||||||
|
@ -88,7 +110,7 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
|
||||||
// close() is done automatically by destructor of SdFile
|
// close() is done automatically by destructor of SdFile
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
char pn0 = p.name[0];
|
uint8_t pn0 = p.name[0];
|
||||||
if (pn0 == DIR_NAME_FREE) break;
|
if (pn0 == DIR_NAME_FREE) break;
|
||||||
if (pn0 == DIR_NAME_DELETED || pn0 == '.') continue;
|
if (pn0 == DIR_NAME_DELETED || pn0 == '.') continue;
|
||||||
if (longFilename[0] == '.') continue;
|
if (longFilename[0] == '.') continue;
|
||||||
|
@ -195,11 +217,7 @@ void CardReader::initsd() {
|
||||||
cardOK = false;
|
cardOK = false;
|
||||||
if (root.isOpen()) root.close();
|
if (root.isOpen()) root.close();
|
||||||
|
|
||||||
#if ENABLED(SDEXTRASLOW)
|
#ifndef SPI_SPEED
|
||||||
#define SPI_SPEED SPI_QUARTER_SPEED
|
|
||||||
#elif ENABLED(SDSLOW)
|
|
||||||
#define SPI_SPEED SPI_HALF_SPEED
|
|
||||||
#else
|
|
||||||
#define SPI_SPEED SPI_FULL_SPEED
|
#define SPI_SPEED SPI_FULL_SPEED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -227,7 +245,7 @@ void CardReader::initsd() {
|
||||||
}
|
}
|
||||||
workDir = root;
|
workDir = root;
|
||||||
curDir = &root;
|
curDir = &root;
|
||||||
/*
|
/**
|
||||||
if (!workDir.openRoot(&volume)) {
|
if (!workDir.openRoot(&volume)) {
|
||||||
SERIAL_ECHOLNPGM(MSG_SD_WORKDIR_FAIL);
|
SERIAL_ECHOLNPGM(MSG_SD_WORKDIR_FAIL);
|
||||||
}
|
}
|
||||||
|
@ -247,6 +265,14 @@ void CardReader::release() {
|
||||||
cardOK = false;
|
cardOK = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void CardReader::openAndPrintFile(const char *name) {
|
||||||
|
char cmd[4 + strlen(name) + 1]; // Room for "M23 ", filename, and null
|
||||||
|
sprintf_P(cmd, PSTR("M23 %s"), name);
|
||||||
|
for (char *c = &cmd[4]; *c; c++) *c = tolower(*c);
|
||||||
|
enqueue_and_echo_command(cmd);
|
||||||
|
enqueue_and_echo_commands_P(PSTR("M24"));
|
||||||
|
}
|
||||||
|
|
||||||
void CardReader::startFileprint() {
|
void CardReader::startFileprint() {
|
||||||
if (cardOK)
|
if (cardOK)
|
||||||
sdprinting = true;
|
sdprinting = true;
|
||||||
|
@ -268,16 +294,16 @@ void CardReader::getAbsFilename(char *t) {
|
||||||
workDirParents[i].getFilename(t); //SDBaseFile.getfilename!
|
workDirParents[i].getFilename(t); //SDBaseFile.getfilename!
|
||||||
while (*t && cnt < MAXPATHNAMELENGTH) { t++; cnt++; } //crawl counter forward.
|
while (*t && cnt < MAXPATHNAMELENGTH) { t++; cnt++; } //crawl counter forward.
|
||||||
}
|
}
|
||||||
if (cnt < MAXPATHNAMELENGTH - FILENAME_LENGTH)
|
if (cnt < MAXPATHNAMELENGTH - (FILENAME_LENGTH))
|
||||||
file.getFilename(t);
|
file.getFilename(t);
|
||||||
else
|
else
|
||||||
t[0] = 0;
|
t[0] = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
void CardReader::openFile(char* name, bool read, bool replace_current/*=true*/) {
|
void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
|
||||||
if (!cardOK) return;
|
if (!cardOK) return;
|
||||||
if (file.isOpen()) { //replacing current file by new file, or subfile call
|
if (file.isOpen()) { //replacing current file by new file, or subfile call
|
||||||
if (!replace_current) {
|
if (push_current) {
|
||||||
if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) {
|
if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) {
|
||||||
SERIAL_ERROR_START;
|
SERIAL_ERROR_START;
|
||||||
SERIAL_ERRORPGM("trying to call sub-gcode files with too many levels. MAX level is:");
|
SERIAL_ERRORPGM("trying to call sub-gcode files with too many levels. MAX level is:");
|
||||||
|
@ -292,20 +318,20 @@ void CardReader::openFile(char* name, bool read, bool replace_current/*=true*/)
|
||||||
SERIAL_ECHOPGM("\" parent:\"");
|
SERIAL_ECHOPGM("\" parent:\"");
|
||||||
|
|
||||||
//store current filename and position
|
//store current filename and position
|
||||||
getAbsFilename(filenames[file_subcall_ctr]);
|
getAbsFilename(proc_filenames[file_subcall_ctr]);
|
||||||
|
|
||||||
SERIAL_ECHO(filenames[file_subcall_ctr]);
|
SERIAL_ECHO(proc_filenames[file_subcall_ctr]);
|
||||||
SERIAL_ECHOPGM("\" pos");
|
SERIAL_ECHOPGM("\" pos");
|
||||||
SERIAL_ECHOLN(sdpos);
|
SERIAL_ECHOLN(sdpos);
|
||||||
filespos[file_subcall_ctr] = sdpos;
|
filespos[file_subcall_ctr] = sdpos;
|
||||||
file_subcall_ctr++;
|
file_subcall_ctr++;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
SERIAL_ECHO_START;
|
SERIAL_ECHO_START;
|
||||||
SERIAL_ECHOPGM("Now doing file: ");
|
SERIAL_ECHOPGM("Now doing file: ");
|
||||||
SERIAL_ECHOLN(name);
|
SERIAL_ECHOLN(name);
|
||||||
}
|
}
|
||||||
file.close();
|
file.close();
|
||||||
}
|
}
|
||||||
else { //opening fresh file
|
else { //opening fresh file
|
||||||
file_subcall_ctr = 0; //resetting procedure depth in case user cancels print while in procedure
|
file_subcall_ctr = 0; //resetting procedure depth in case user cancels print while in procedure
|
||||||
|
@ -322,11 +348,11 @@ void CardReader::openFile(char* name, bool read, bool replace_current/*=true*/)
|
||||||
char *dirname_start, *dirname_end;
|
char *dirname_start, *dirname_end;
|
||||||
if (name[0] == '/') {
|
if (name[0] == '/') {
|
||||||
dirname_start = &name[1];
|
dirname_start = &name[1];
|
||||||
while (dirname_start > 0) {
|
while (dirname_start != NULL) {
|
||||||
dirname_end = strchr(dirname_start, '/');
|
dirname_end = strchr(dirname_start, '/');
|
||||||
//SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start - name));
|
//SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start - name));
|
||||||
//SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end - name));
|
//SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end - name));
|
||||||
if (dirname_end > 0 && dirname_end > dirname_start) {
|
if (dirname_end != NULL && dirname_end > dirname_start) {
|
||||||
char subdirname[FILENAME_LENGTH];
|
char subdirname[FILENAME_LENGTH];
|
||||||
strncpy(subdirname, dirname_start, dirname_end - dirname_start);
|
strncpy(subdirname, dirname_start, dirname_end - dirname_start);
|
||||||
subdirname[dirname_end - dirname_start] = 0;
|
subdirname[dirname_end - dirname_start] = 0;
|
||||||
|
@ -403,11 +429,11 @@ void CardReader::removeFile(char* name) {
|
||||||
char *dirname_start, *dirname_end;
|
char *dirname_start, *dirname_end;
|
||||||
if (name[0] == '/') {
|
if (name[0] == '/') {
|
||||||
dirname_start = strchr(name, '/') + 1;
|
dirname_start = strchr(name, '/') + 1;
|
||||||
while (dirname_start > 0) {
|
while (dirname_start != NULL) {
|
||||||
dirname_end = strchr(dirname_start, '/');
|
dirname_end = strchr(dirname_start, '/');
|
||||||
//SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start - name));
|
//SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start - name));
|
||||||
//SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end - name));
|
//SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end - name));
|
||||||
if (dirname_end > 0 && dirname_end > dirname_start) {
|
if (dirname_end != NULL && dirname_end > dirname_start) {
|
||||||
char subdirname[FILENAME_LENGTH];
|
char subdirname[FILENAME_LENGTH];
|
||||||
strncpy(subdirname, dirname_start, dirname_end - dirname_start);
|
strncpy(subdirname, dirname_start, dirname_end - dirname_start);
|
||||||
subdirname[dirname_end - dirname_start] = 0;
|
subdirname[dirname_end - dirname_start] = 0;
|
||||||
|
@ -504,10 +530,7 @@ void CardReader::checkautostart(bool force) {
|
||||||
while (root.readDir(p, NULL) > 0) {
|
while (root.readDir(p, NULL) > 0) {
|
||||||
for (int8_t i = 0; i < (int8_t)strlen((char*)p.name); i++) p.name[i] = tolower(p.name[i]);
|
for (int8_t i = 0; i < (int8_t)strlen((char*)p.name); i++) p.name[i] = tolower(p.name[i]);
|
||||||
if (p.name[9] != '~' && strncmp((char*)p.name, autoname, 5) == 0) {
|
if (p.name[9] != '~' && strncmp((char*)p.name, autoname, 5) == 0) {
|
||||||
char cmd[4 + (FILENAME_LENGTH + 1) * MAX_DIR_DEPTH + 2];
|
openAndPrintFile(autoname);
|
||||||
sprintf_P(cmd, PSTR("M23 %s"), autoname);
|
|
||||||
enqueuecommand(cmd);
|
|
||||||
enqueuecommands_P(PSTR("M24"));
|
|
||||||
found = true;
|
found = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -561,22 +584,15 @@ void CardReader::chdir(const char * relpath) {
|
||||||
SERIAL_ECHOLN(relpath);
|
SERIAL_ECHOLN(relpath);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
if (workDirDepth < MAX_DIR_DEPTH) {
|
if (workDirDepth < MAX_DIR_DEPTH)
|
||||||
++workDirDepth;
|
workDirParents[workDirDepth++] = *parent;
|
||||||
for (int d = workDirDepth; d--;) workDirParents[d + 1] = workDirParents[d];
|
|
||||||
workDirParents[0] = *parent;
|
|
||||||
}
|
|
||||||
workDir = newfile;
|
workDir = newfile;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void CardReader::updir() {
|
void CardReader::updir() {
|
||||||
if (workDirDepth > 0) {
|
if (workDirDepth > 0)
|
||||||
--workDirDepth;
|
workDir = workDirParents[--workDirDepth];
|
||||||
workDir = workDirParents[0];
|
|
||||||
for (uint16_t d = 0; d < workDirDepth; d++)
|
|
||||||
workDirParents[d] = workDirParents[d+1];
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void CardReader::printingHasFinished() {
|
void CardReader::printingHasFinished() {
|
||||||
|
@ -584,17 +600,15 @@ void CardReader::printingHasFinished() {
|
||||||
if (file_subcall_ctr > 0) { // Heading up to a parent file that called current as a procedure.
|
if (file_subcall_ctr > 0) { // Heading up to a parent file that called current as a procedure.
|
||||||
file.close();
|
file.close();
|
||||||
file_subcall_ctr--;
|
file_subcall_ctr--;
|
||||||
openFile(filenames[file_subcall_ctr], true, true);
|
openFile(proc_filenames[file_subcall_ctr], true, true);
|
||||||
setIndex(filespos[file_subcall_ctr]);
|
setIndex(filespos[file_subcall_ctr]);
|
||||||
startFileprint();
|
startFileprint();
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
file.close();
|
file.close();
|
||||||
sdprinting = false;
|
sdprinting = false;
|
||||||
if (SD_FINISHED_STEPPERRELEASE) {
|
if (SD_FINISHED_STEPPERRELEASE)
|
||||||
//finishAndDisableSteppers();
|
enqueue_and_echo_commands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
|
||||||
enqueuecommands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
|
|
||||||
}
|
|
||||||
autotempShutdown();
|
autotempShutdown();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,3 +1,25 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
#ifndef CARDREADER_H
|
#ifndef CARDREADER_H
|
||||||
#define CARDREADER_H
|
#define CARDREADER_H
|
||||||
|
|
||||||
|
@ -18,11 +40,12 @@ public:
|
||||||
//this is to delay autostart and hence the initialisaiton of the sd card to some seconds after the normal init, so the device is available quick after a reset
|
//this is to delay autostart and hence the initialisaiton of the sd card to some seconds after the normal init, so the device is available quick after a reset
|
||||||
|
|
||||||
void checkautostart(bool x);
|
void checkautostart(bool x);
|
||||||
void openFile(char* name,bool read,bool replace_current=true);
|
void openFile(char* name, bool read, bool push_current=false);
|
||||||
void openLogFile(char* name);
|
void openLogFile(char* name);
|
||||||
void removeFile(char* name);
|
void removeFile(char* name);
|
||||||
void closefile(bool store_location=false);
|
void closefile(bool store_location=false);
|
||||||
void release();
|
void release();
|
||||||
|
void openAndPrintFile(const char *name);
|
||||||
void startFileprint();
|
void startFileprint();
|
||||||
void pauseSDPrint();
|
void pauseSDPrint();
|
||||||
void getStatus();
|
void getStatus();
|
||||||
|
@ -42,7 +65,6 @@ public:
|
||||||
void updir();
|
void updir();
|
||||||
void setroot();
|
void setroot();
|
||||||
|
|
||||||
|
|
||||||
FORCE_INLINE bool isFileOpen() { return file.isOpen(); }
|
FORCE_INLINE bool isFileOpen() { return file.isOpen(); }
|
||||||
FORCE_INLINE bool eof() { return sdpos >= filesize; }
|
FORCE_INLINE bool eof() { return sdpos >= filesize; }
|
||||||
FORCE_INLINE int16_t get() { sdpos = file.curPosition(); return (int16_t)file.read(); }
|
FORCE_INLINE int16_t get() { sdpos = file.curPosition(); return (int16_t)file.read(); }
|
||||||
|
@ -56,19 +78,20 @@ public:
|
||||||
int autostart_index;
|
int autostart_index;
|
||||||
private:
|
private:
|
||||||
SdFile root, *curDir, workDir, workDirParents[MAX_DIR_DEPTH];
|
SdFile root, *curDir, workDir, workDirParents[MAX_DIR_DEPTH];
|
||||||
uint16_t workDirDepth;
|
uint8_t workDirDepth;
|
||||||
Sd2Card card;
|
Sd2Card card;
|
||||||
SdVolume volume;
|
SdVolume volume;
|
||||||
SdFile file;
|
SdFile file;
|
||||||
|
|
||||||
#define SD_PROCEDURE_DEPTH 1
|
#define SD_PROCEDURE_DEPTH 1
|
||||||
#define MAXPATHNAMELENGTH (FILENAME_LENGTH*MAX_DIR_DEPTH + MAX_DIR_DEPTH + 1)
|
#define MAXPATHNAMELENGTH (FILENAME_LENGTH*MAX_DIR_DEPTH + MAX_DIR_DEPTH + 1)
|
||||||
uint8_t file_subcall_ctr;
|
uint8_t file_subcall_ctr;
|
||||||
uint32_t filespos[SD_PROCEDURE_DEPTH];
|
uint32_t filespos[SD_PROCEDURE_DEPTH];
|
||||||
char filenames[SD_PROCEDURE_DEPTH][MAXPATHNAMELENGTH];
|
char proc_filenames[SD_PROCEDURE_DEPTH][MAXPATHNAMELENGTH];
|
||||||
uint32_t filesize;
|
uint32_t filesize;
|
||||||
millis_t next_autostart_ms;
|
|
||||||
uint32_t sdpos;
|
uint32_t sdpos;
|
||||||
|
|
||||||
|
millis_t next_autostart_ms;
|
||||||
bool autostart_stilltocheck; //the sd start is delayed, because otherwise the serial cannot answer fast enought to make contact with the hostsoftware.
|
bool autostart_stilltocheck; //the sd start is delayed, because otherwise the serial cannot answer fast enought to make contact with the hostsoftware.
|
||||||
|
|
||||||
LsAction lsAction; //stored for recursion.
|
LsAction lsAction; //stored for recursion.
|
||||||
|
|
|
@ -1,3 +1,25 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* configuration_store.cpp
|
* configuration_store.cpp
|
||||||
*
|
*
|
||||||
|
@ -14,79 +36,88 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define EEPROM_VERSION "V21"
|
#define EEPROM_VERSION "V23"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* V19 EEPROM Layout:
|
* V23 EEPROM Layout:
|
||||||
*
|
*
|
||||||
* ver
|
* 100 Version (char x4)
|
||||||
* M92 XYZE axis_steps_per_unit (x4)
|
*
|
||||||
* M203 XYZE max_feedrate (x4)
|
* 104 M92 XYZE axis_steps_per_unit (float x4)
|
||||||
* M201 XYZE max_acceleration_units_per_sq_second (x4)
|
* 120 M203 XYZE max_feedrate (float x4)
|
||||||
* M204 P acceleration
|
* 136 M201 XYZE max_acceleration_units_per_sq_second (uint32_t x4)
|
||||||
* M204 R retract_acceleration
|
* 152 M204 P acceleration (float)
|
||||||
* M204 T travel_acceleration
|
* 156 M204 R retract_acceleration (float)
|
||||||
* M205 S minimumfeedrate
|
* 160 M204 T travel_acceleration (float)
|
||||||
* M205 T mintravelfeedrate
|
* 164 M205 S minimumfeedrate (float)
|
||||||
* M205 B minsegmenttime
|
* 168 M205 T mintravelfeedrate (float)
|
||||||
* M205 X max_xy_jerk
|
* 172 M205 B minsegmenttime (ulong)
|
||||||
* M205 Z max_z_jerk
|
* 176 M205 X max_xy_jerk (float)
|
||||||
* M205 E max_e_jerk
|
* 180 M205 Z max_z_jerk (float)
|
||||||
* M206 XYZ home_offset (x3)
|
* 184 M205 E max_e_jerk (float)
|
||||||
|
* 188 M206 XYZ home_offset (float x3)
|
||||||
*
|
*
|
||||||
* Mesh bed leveling:
|
* Mesh bed leveling:
|
||||||
* M420 S active
|
* 200 M420 S active (bool)
|
||||||
* mesh_num_x (set in firmware)
|
* 201 z_offset (float) (added in V23)
|
||||||
* mesh_num_y (set in firmware)
|
* 205 mesh_num_x (uint8 as set in firmware)
|
||||||
* M421 XYZ z_values[][]
|
* 206 mesh_num_y (uint8 as set in firmware)
|
||||||
* M851 zprobe_zoffset
|
* 207 M421 XYZ z_values[][] (float x9, by default)
|
||||||
|
*
|
||||||
|
* AUTO BED LEVELING
|
||||||
|
* 243 M851 zprobe_zoffset (float)
|
||||||
*
|
*
|
||||||
* DELTA:
|
* DELTA:
|
||||||
* M666 XYZ endstop_adj (x3)
|
* 247 M666 XYZ endstop_adj (float x3)
|
||||||
* M665 R delta_radius
|
* 259 M665 R delta_radius (float)
|
||||||
* M665 L delta_diagonal_rod
|
* 263 M665 L delta_diagonal_rod (float)
|
||||||
* M665 S delta_segments_per_second
|
* 267 M665 S delta_segments_per_second (float)
|
||||||
*
|
* 271 M665 A delta_diagonal_rod_trim_tower_1 (float)
|
||||||
* ULTIPANEL:
|
* 275 M665 B delta_diagonal_rod_trim_tower_2 (float)
|
||||||
* M145 S0 H plaPreheatHotendTemp
|
* 279 M665 C delta_diagonal_rod_trim_tower_3 (float)
|
||||||
* M145 S0 B plaPreheatHPBTemp
|
|
||||||
* M145 S0 F plaPreheatFanSpeed
|
|
||||||
* M145 S1 H absPreheatHotendTemp
|
|
||||||
* M145 S1 B absPreheatHPBTemp
|
|
||||||
* M145 S1 F absPreheatFanSpeed
|
|
||||||
*
|
|
||||||
* PIDTEMP:
|
|
||||||
* M301 E0 PIDC Kp[0], Ki[0], Kd[0], Kc[0]
|
|
||||||
* M301 E1 PIDC Kp[1], Ki[1], Kd[1], Kc[1]
|
|
||||||
* M301 E2 PIDC Kp[2], Ki[2], Kd[2], Kc[2]
|
|
||||||
* M301 E3 PIDC Kp[3], Ki[3], Kd[3], Kc[3]
|
|
||||||
* M301 L lpq_len
|
|
||||||
*
|
|
||||||
* PIDTEMPBED:
|
|
||||||
* M304 PID bedKp, bedKi, bedKd
|
|
||||||
*
|
|
||||||
* DOGLCD:
|
|
||||||
* M250 C lcd_contrast
|
|
||||||
*
|
|
||||||
* SCARA:
|
|
||||||
* M365 XYZ axis_scaling (x3)
|
|
||||||
*
|
|
||||||
* FWRETRACT:
|
|
||||||
* M209 S autoretract_enabled
|
|
||||||
* M207 S retract_length
|
|
||||||
* M207 W retract_length_swap
|
|
||||||
* M207 F retract_feedrate
|
|
||||||
* M207 Z retract_zlift
|
|
||||||
* M208 S retract_recover_length
|
|
||||||
* M208 W retract_recover_length_swap
|
|
||||||
* M208 F retract_recover_feedrate
|
|
||||||
*
|
|
||||||
* M200 D volumetric_enabled (D>0 makes this enabled)
|
|
||||||
*
|
|
||||||
* M200 T D filament_size (x4) (T0..3)
|
|
||||||
*
|
*
|
||||||
* Z_DUAL_ENDSTOPS:
|
* Z_DUAL_ENDSTOPS:
|
||||||
* M666 Z z_endstop_adj
|
* 283 M666 Z z_endstop_adj (float)
|
||||||
|
*
|
||||||
|
* ULTIPANEL:
|
||||||
|
* 287 M145 S0 H plaPreheatHotendTemp (int)
|
||||||
|
* 289 M145 S0 B plaPreheatHPBTemp (int)
|
||||||
|
* 291 M145 S0 F plaPreheatFanSpeed (int)
|
||||||
|
* 293 M145 S1 H absPreheatHotendTemp (int)
|
||||||
|
* 295 M145 S1 B absPreheatHPBTemp (int)
|
||||||
|
* 297 M145 S1 F absPreheatFanSpeed (int)
|
||||||
|
*
|
||||||
|
* PIDTEMP:
|
||||||
|
* 299 M301 E0 PIDC Kp[0], Ki[0], Kd[0], Kc[0] (float x4)
|
||||||
|
* 315 M301 E1 PIDC Kp[1], Ki[1], Kd[1], Kc[1] (float x4)
|
||||||
|
* 331 M301 E2 PIDC Kp[2], Ki[2], Kd[2], Kc[2] (float x4)
|
||||||
|
* 347 M301 E3 PIDC Kp[3], Ki[3], Kd[3], Kc[3] (float x4)
|
||||||
|
* 363 M301 L lpq_len (int)
|
||||||
|
*
|
||||||
|
* PIDTEMPBED:
|
||||||
|
* 365 M304 PID bedKp, bedKi, bedKd (float x3)
|
||||||
|
*
|
||||||
|
* DOGLCD:
|
||||||
|
* 377 M250 C lcd_contrast (int)
|
||||||
|
*
|
||||||
|
* SCARA:
|
||||||
|
* 379 M365 XYZ axis_scaling (float x3)
|
||||||
|
*
|
||||||
|
* FWRETRACT:
|
||||||
|
* 391 M209 S autoretract_enabled (bool)
|
||||||
|
* 392 M207 S retract_length (float)
|
||||||
|
* 396 M207 W retract_length_swap (float)
|
||||||
|
* 400 M207 F retract_feedrate (float)
|
||||||
|
* 404 M207 Z retract_zlift (float)
|
||||||
|
* 408 M208 S retract_recover_length (float)
|
||||||
|
* 412 M208 W retract_recover_length_swap (float)
|
||||||
|
* 416 M208 F retract_recover_feedrate (float)
|
||||||
|
*
|
||||||
|
* Volumetric Extrusion:
|
||||||
|
* 420 M200 D volumetric_enabled (bool)
|
||||||
|
* 421 M200 T D filament_size (float x4) (T0..3)
|
||||||
|
*
|
||||||
|
* 437 This Slot is Available!
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#include "Marlin.h"
|
||||||
|
@ -133,6 +164,10 @@ void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size) {
|
||||||
|
|
||||||
#if ENABLED(EEPROM_SETTINGS)
|
#if ENABLED(EEPROM_SETTINGS)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Store Configuration Settings - M500
|
||||||
|
*/
|
||||||
|
|
||||||
void Config_StoreSettings() {
|
void Config_StoreSettings() {
|
||||||
float dummy = 0.0f;
|
float dummy = 0.0f;
|
||||||
char ver[4] = "000";
|
char ver[4] = "000";
|
||||||
|
@ -156,19 +191,21 @@ void Config_StoreSettings() {
|
||||||
uint8_t mesh_num_y = 3;
|
uint8_t mesh_num_y = 3;
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
// Compile time test that sizeof(mbl.z_values) is as expected
|
// Compile time test that sizeof(mbl.z_values) is as expected
|
||||||
typedef char c_assert[(sizeof(mbl.z_values) == MESH_NUM_X_POINTS * MESH_NUM_Y_POINTS * sizeof(dummy)) ? 1 : -1];
|
typedef char c_assert[(sizeof(mbl.z_values) == (MESH_NUM_X_POINTS) * (MESH_NUM_Y_POINTS) * sizeof(dummy)) ? 1 : -1];
|
||||||
mesh_num_x = MESH_NUM_X_POINTS;
|
mesh_num_x = MESH_NUM_X_POINTS;
|
||||||
mesh_num_y = MESH_NUM_Y_POINTS;
|
mesh_num_y = MESH_NUM_Y_POINTS;
|
||||||
EEPROM_WRITE_VAR(i, mbl.active);
|
EEPROM_WRITE_VAR(i, mbl.active);
|
||||||
|
EEPROM_WRITE_VAR(i, mbl.z_offset);
|
||||||
EEPROM_WRITE_VAR(i, mesh_num_x);
|
EEPROM_WRITE_VAR(i, mesh_num_x);
|
||||||
EEPROM_WRITE_VAR(i, mesh_num_y);
|
EEPROM_WRITE_VAR(i, mesh_num_y);
|
||||||
EEPROM_WRITE_VAR(i, mbl.z_values);
|
EEPROM_WRITE_VAR(i, mbl.z_values);
|
||||||
#else
|
#else
|
||||||
uint8_t dummy_uint8 = 0;
|
uint8_t dummy_uint8 = 0;
|
||||||
|
dummy = 0.0f;
|
||||||
EEPROM_WRITE_VAR(i, dummy_uint8);
|
EEPROM_WRITE_VAR(i, dummy_uint8);
|
||||||
|
EEPROM_WRITE_VAR(i, dummy);
|
||||||
EEPROM_WRITE_VAR(i, mesh_num_x);
|
EEPROM_WRITE_VAR(i, mesh_num_x);
|
||||||
EEPROM_WRITE_VAR(i, mesh_num_y);
|
EEPROM_WRITE_VAR(i, mesh_num_y);
|
||||||
dummy = 0.0f;
|
|
||||||
for (uint8_t q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_WRITE_VAR(i, dummy);
|
for (uint8_t q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_WRITE_VAR(i, dummy);
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
|
@ -182,13 +219,16 @@ void Config_StoreSettings() {
|
||||||
EEPROM_WRITE_VAR(i, delta_radius); // 1 float
|
EEPROM_WRITE_VAR(i, delta_radius); // 1 float
|
||||||
EEPROM_WRITE_VAR(i, delta_diagonal_rod); // 1 float
|
EEPROM_WRITE_VAR(i, delta_diagonal_rod); // 1 float
|
||||||
EEPROM_WRITE_VAR(i, delta_segments_per_second); // 1 float
|
EEPROM_WRITE_VAR(i, delta_segments_per_second); // 1 float
|
||||||
|
EEPROM_WRITE_VAR(i, delta_diagonal_rod_trim_tower_1); // 1 float
|
||||||
|
EEPROM_WRITE_VAR(i, delta_diagonal_rod_trim_tower_2); // 1 float
|
||||||
|
EEPROM_WRITE_VAR(i, delta_diagonal_rod_trim_tower_3); // 1 float
|
||||||
#elif ENABLED(Z_DUAL_ENDSTOPS)
|
#elif ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
EEPROM_WRITE_VAR(i, z_endstop_adj); // 1 floats
|
EEPROM_WRITE_VAR(i, z_endstop_adj); // 1 float
|
||||||
dummy = 0.0f;
|
dummy = 0.0f;
|
||||||
for (int q = 5; q--;) EEPROM_WRITE_VAR(i, dummy);
|
for (uint8_t q = 8; q--;) EEPROM_WRITE_VAR(i, dummy);
|
||||||
#else
|
#else
|
||||||
dummy = 0.0f;
|
dummy = 0.0f;
|
||||||
for (int q = 6; q--;) EEPROM_WRITE_VAR(i, dummy);
|
for (uint8_t q = 9; q--;) EEPROM_WRITE_VAR(i, dummy);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if DISABLED(ULTIPANEL)
|
#if DISABLED(ULTIPANEL)
|
||||||
|
@ -203,7 +243,7 @@ void Config_StoreSettings() {
|
||||||
EEPROM_WRITE_VAR(i, absPreheatHPBTemp);
|
EEPROM_WRITE_VAR(i, absPreheatHPBTemp);
|
||||||
EEPROM_WRITE_VAR(i, absPreheatFanSpeed);
|
EEPROM_WRITE_VAR(i, absPreheatFanSpeed);
|
||||||
|
|
||||||
for (int e = 0; e < 4; e++) {
|
for (uint8_t e = 0; e < 4; e++) {
|
||||||
|
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
if (e < EXTRUDERS) {
|
if (e < EXTRUDERS) {
|
||||||
|
@ -223,7 +263,7 @@ void Config_StoreSettings() {
|
||||||
dummy = DUMMY_PID_VALUE; // When read, will not change the existing value
|
dummy = DUMMY_PID_VALUE; // When read, will not change the existing value
|
||||||
EEPROM_WRITE_VAR(i, dummy);
|
EEPROM_WRITE_VAR(i, dummy);
|
||||||
dummy = 0.0f;
|
dummy = 0.0f;
|
||||||
for (int q = 3; q--;) EEPROM_WRITE_VAR(i, dummy);
|
for (uint8_t q = 3; q--;) EEPROM_WRITE_VAR(i, dummy);
|
||||||
}
|
}
|
||||||
|
|
||||||
} // Extruders Loop
|
} // Extruders Loop
|
||||||
|
@ -277,7 +317,7 @@ void Config_StoreSettings() {
|
||||||
EEPROM_WRITE_VAR(i, volumetric_enabled);
|
EEPROM_WRITE_VAR(i, volumetric_enabled);
|
||||||
|
|
||||||
// Save filament sizes
|
// Save filament sizes
|
||||||
for (int q = 0; q < 4; q++) {
|
for (uint8_t q = 0; q < 4; q++) {
|
||||||
if (q < EXTRUDERS) dummy = filament_size[q];
|
if (q < EXTRUDERS) dummy = filament_size[q];
|
||||||
EEPROM_WRITE_VAR(i, dummy);
|
EEPROM_WRITE_VAR(i, dummy);
|
||||||
}
|
}
|
||||||
|
@ -331,18 +371,20 @@ void Config_RetrieveSettings() {
|
||||||
|
|
||||||
uint8_t dummy_uint8 = 0, mesh_num_x = 0, mesh_num_y = 0;
|
uint8_t dummy_uint8 = 0, mesh_num_x = 0, mesh_num_y = 0;
|
||||||
EEPROM_READ_VAR(i, dummy_uint8);
|
EEPROM_READ_VAR(i, dummy_uint8);
|
||||||
|
EEPROM_READ_VAR(i, dummy);
|
||||||
EEPROM_READ_VAR(i, mesh_num_x);
|
EEPROM_READ_VAR(i, mesh_num_x);
|
||||||
EEPROM_READ_VAR(i, mesh_num_y);
|
EEPROM_READ_VAR(i, mesh_num_y);
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
mbl.active = dummy_uint8;
|
mbl.active = dummy_uint8;
|
||||||
|
mbl.z_offset = dummy;
|
||||||
if (mesh_num_x == MESH_NUM_X_POINTS && mesh_num_y == MESH_NUM_Y_POINTS) {
|
if (mesh_num_x == MESH_NUM_X_POINTS && mesh_num_y == MESH_NUM_Y_POINTS) {
|
||||||
EEPROM_READ_VAR(i, mbl.z_values);
|
EEPROM_READ_VAR(i, mbl.z_values);
|
||||||
} else {
|
} else {
|
||||||
mbl.reset();
|
mbl.reset();
|
||||||
for (int q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_READ_VAR(i, dummy);
|
for (uint8_t q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_READ_VAR(i, dummy);
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
for (int q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_READ_VAR(i, dummy);
|
for (uint8_t q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_READ_VAR(i, dummy);
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
#if DISABLED(AUTO_BED_LEVELING_FEATURE)
|
#if DISABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
@ -355,13 +397,16 @@ void Config_RetrieveSettings() {
|
||||||
EEPROM_READ_VAR(i, delta_radius); // 1 float
|
EEPROM_READ_VAR(i, delta_radius); // 1 float
|
||||||
EEPROM_READ_VAR(i, delta_diagonal_rod); // 1 float
|
EEPROM_READ_VAR(i, delta_diagonal_rod); // 1 float
|
||||||
EEPROM_READ_VAR(i, delta_segments_per_second); // 1 float
|
EEPROM_READ_VAR(i, delta_segments_per_second); // 1 float
|
||||||
|
EEPROM_READ_VAR(i, delta_diagonal_rod_trim_tower_1); // 1 float
|
||||||
|
EEPROM_READ_VAR(i, delta_diagonal_rod_trim_tower_2); // 1 float
|
||||||
|
EEPROM_READ_VAR(i, delta_diagonal_rod_trim_tower_3); // 1 float
|
||||||
#elif ENABLED(Z_DUAL_ENDSTOPS)
|
#elif ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
EEPROM_READ_VAR(i, z_endstop_adj);
|
EEPROM_READ_VAR(i, z_endstop_adj);
|
||||||
dummy = 0.0f;
|
dummy = 0.0f;
|
||||||
for (int q=5; q--;) EEPROM_READ_VAR(i, dummy);
|
for (uint8_t q=8; q--;) EEPROM_READ_VAR(i, dummy);
|
||||||
#else
|
#else
|
||||||
dummy = 0.0f;
|
dummy = 0.0f;
|
||||||
for (int q=6; q--;) EEPROM_READ_VAR(i, dummy);
|
for (uint8_t q=9; q--;) EEPROM_READ_VAR(i, dummy);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if DISABLED(ULTIPANEL)
|
#if DISABLED(ULTIPANEL)
|
||||||
|
@ -377,7 +422,7 @@ void Config_RetrieveSettings() {
|
||||||
EEPROM_READ_VAR(i, absPreheatFanSpeed);
|
EEPROM_READ_VAR(i, absPreheatFanSpeed);
|
||||||
|
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
for (int e = 0; e < 4; e++) { // 4 = max extruders currently supported by Marlin
|
for (uint8_t e = 0; e < 4; e++) { // 4 = max extruders currently supported by Marlin
|
||||||
EEPROM_READ_VAR(i, dummy); // Kp
|
EEPROM_READ_VAR(i, dummy); // Kp
|
||||||
if (e < EXTRUDERS && dummy != DUMMY_PID_VALUE) {
|
if (e < EXTRUDERS && dummy != DUMMY_PID_VALUE) {
|
||||||
// do not need to scale PID values as the values in EEPROM are already scaled
|
// do not need to scale PID values as the values in EEPROM are already scaled
|
||||||
|
@ -391,12 +436,12 @@ void Config_RetrieveSettings() {
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
for (int q=3; q--;) EEPROM_READ_VAR(i, dummy); // Ki, Kd, Kc
|
for (uint8_t q=3; q--;) EEPROM_READ_VAR(i, dummy); // Ki, Kd, Kc
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#else // !PIDTEMP
|
#else // !PIDTEMP
|
||||||
// 4 x 4 = 16 slots for PID parameters
|
// 4 x 4 = 16 slots for PID parameters
|
||||||
for (int q=16; q--;) EEPROM_READ_VAR(i, dummy); // 4x Kp, Ki, Kd, Kc
|
for (uint8_t q=16; q--;) EEPROM_READ_VAR(i, dummy); // 4x Kp, Ki, Kd, Kc
|
||||||
#endif // !PIDTEMP
|
#endif // !PIDTEMP
|
||||||
|
|
||||||
#if DISABLED(PID_ADD_EXTRUSION_RATE)
|
#if DISABLED(PID_ADD_EXTRUSION_RATE)
|
||||||
|
@ -415,7 +460,7 @@ void Config_RetrieveSettings() {
|
||||||
EEPROM_READ_VAR(i, bedKd);
|
EEPROM_READ_VAR(i, bedKd);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
for (int q=2; q--;) EEPROM_READ_VAR(i, dummy); // bedKi, bedKd
|
for (uint8_t q=2; q--;) EEPROM_READ_VAR(i, dummy); // bedKi, bedKd
|
||||||
}
|
}
|
||||||
|
|
||||||
#if DISABLED(HAS_LCD_CONTRAST)
|
#if DISABLED(HAS_LCD_CONTRAST)
|
||||||
|
@ -450,7 +495,7 @@ void Config_RetrieveSettings() {
|
||||||
|
|
||||||
EEPROM_READ_VAR(i, volumetric_enabled);
|
EEPROM_READ_VAR(i, volumetric_enabled);
|
||||||
|
|
||||||
for (int q = 0; q < 4; q++) {
|
for (uint8_t q = 0; q < 4; q++) {
|
||||||
EEPROM_READ_VAR(i, dummy);
|
EEPROM_READ_VAR(i, dummy);
|
||||||
if (q < EXTRUDERS) filament_size[q] = dummy;
|
if (q < EXTRUDERS) filament_size[q] = dummy;
|
||||||
}
|
}
|
||||||
|
@ -518,6 +563,9 @@ void Config_ResetDefault() {
|
||||||
delta_radius = DELTA_RADIUS;
|
delta_radius = DELTA_RADIUS;
|
||||||
delta_diagonal_rod = DELTA_DIAGONAL_ROD;
|
delta_diagonal_rod = DELTA_DIAGONAL_ROD;
|
||||||
delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND;
|
delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND;
|
||||||
|
delta_diagonal_rod_trim_tower_1 = DELTA_DIAGONAL_ROD_TRIM_TOWER_1;
|
||||||
|
delta_diagonal_rod_trim_tower_2 = DELTA_DIAGONAL_ROD_TRIM_TOWER_2;
|
||||||
|
delta_diagonal_rod_trim_tower_3 = DELTA_DIAGONAL_ROD_TRIM_TOWER_3;
|
||||||
recalc_delta_settings(delta_radius, delta_diagonal_rod);
|
recalc_delta_settings(delta_radius, delta_diagonal_rod);
|
||||||
#elif ENABLED(Z_DUAL_ENDSTOPS)
|
#elif ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
z_endstop_adj = 0;
|
z_endstop_adj = 0;
|
||||||
|
@ -538,7 +586,7 @@ void Config_ResetDefault() {
|
||||||
|
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
#if ENABLED(PID_PARAMS_PER_EXTRUDER)
|
#if ENABLED(PID_PARAMS_PER_EXTRUDER)
|
||||||
for (int e = 0; e < EXTRUDERS; e++)
|
for (uint8_t e = 0; e < EXTRUDERS; e++)
|
||||||
#else
|
#else
|
||||||
int e = 0; UNUSED(e); // only need to write once
|
int e = 0; UNUSED(e); // only need to write once
|
||||||
#endif
|
#endif
|
||||||
|
@ -686,8 +734,8 @@ void Config_PrintSettings(bool forReplay) {
|
||||||
SERIAL_ECHOPAIR(" X", (unsigned long)MESH_NUM_X_POINTS);
|
SERIAL_ECHOPAIR(" X", (unsigned long)MESH_NUM_X_POINTS);
|
||||||
SERIAL_ECHOPAIR(" Y", (unsigned long)MESH_NUM_Y_POINTS);
|
SERIAL_ECHOPAIR(" Y", (unsigned long)MESH_NUM_Y_POINTS);
|
||||||
SERIAL_EOL;
|
SERIAL_EOL;
|
||||||
for (int y = 0; y < MESH_NUM_Y_POINTS; y++) {
|
for (uint8_t y = 0; y < MESH_NUM_Y_POINTS; y++) {
|
||||||
for (int x = 0; x < MESH_NUM_X_POINTS; x++) {
|
for (uint8_t x = 0; x < MESH_NUM_X_POINTS; x++) {
|
||||||
CONFIG_ECHO_START;
|
CONFIG_ECHO_START;
|
||||||
SERIAL_ECHOPAIR(" M421 X", mbl.get_x(x));
|
SERIAL_ECHOPAIR(" M421 X", mbl.get_x(x));
|
||||||
SERIAL_ECHOPAIR(" Y", mbl.get_y(y));
|
SERIAL_ECHOPAIR(" Y", mbl.get_y(y));
|
||||||
|
@ -708,11 +756,16 @@ void Config_PrintSettings(bool forReplay) {
|
||||||
SERIAL_ECHOPAIR(" Z", endstop_adj[Z_AXIS]);
|
SERIAL_ECHOPAIR(" Z", endstop_adj[Z_AXIS]);
|
||||||
SERIAL_EOL;
|
SERIAL_EOL;
|
||||||
CONFIG_ECHO_START;
|
CONFIG_ECHO_START;
|
||||||
SERIAL_ECHOLNPGM("Delta settings: L=delta_diagonal_rod, R=delta_radius, S=delta_segments_per_second");
|
if (!forReplay) {
|
||||||
CONFIG_ECHO_START;
|
SERIAL_ECHOLNPGM("Delta settings: L=diagonal_rod, R=radius, S=segments_per_second, ABC=diagonal_rod_trim_tower_[123]");
|
||||||
|
CONFIG_ECHO_START;
|
||||||
|
}
|
||||||
SERIAL_ECHOPAIR(" M665 L", delta_diagonal_rod);
|
SERIAL_ECHOPAIR(" M665 L", delta_diagonal_rod);
|
||||||
SERIAL_ECHOPAIR(" R", delta_radius);
|
SERIAL_ECHOPAIR(" R", delta_radius);
|
||||||
SERIAL_ECHOPAIR(" S", delta_segments_per_second);
|
SERIAL_ECHOPAIR(" S", delta_segments_per_second);
|
||||||
|
SERIAL_ECHOPAIR(" A", delta_diagonal_rod_trim_tower_1);
|
||||||
|
SERIAL_ECHOPAIR(" B", delta_diagonal_rod_trim_tower_2);
|
||||||
|
SERIAL_ECHOPAIR(" C", delta_diagonal_rod_trim_tower_3);
|
||||||
SERIAL_EOL;
|
SERIAL_EOL;
|
||||||
#elif ENABLED(Z_DUAL_ENDSTOPS)
|
#elif ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
CONFIG_ECHO_START;
|
CONFIG_ECHO_START;
|
||||||
|
@ -730,12 +783,12 @@ void Config_PrintSettings(bool forReplay) {
|
||||||
SERIAL_ECHOLNPGM("Material heatup parameters:");
|
SERIAL_ECHOLNPGM("Material heatup parameters:");
|
||||||
CONFIG_ECHO_START;
|
CONFIG_ECHO_START;
|
||||||
}
|
}
|
||||||
SERIAL_ECHOPAIR(" M145 M0 H", (unsigned long)plaPreheatHotendTemp);
|
SERIAL_ECHOPAIR(" M145 S0 H", (unsigned long)plaPreheatHotendTemp);
|
||||||
SERIAL_ECHOPAIR(" B", (unsigned long)plaPreheatHPBTemp);
|
SERIAL_ECHOPAIR(" B", (unsigned long)plaPreheatHPBTemp);
|
||||||
SERIAL_ECHOPAIR(" F", (unsigned long)plaPreheatFanSpeed);
|
SERIAL_ECHOPAIR(" F", (unsigned long)plaPreheatFanSpeed);
|
||||||
SERIAL_EOL;
|
SERIAL_EOL;
|
||||||
CONFIG_ECHO_START;
|
CONFIG_ECHO_START;
|
||||||
SERIAL_ECHOPAIR(" M145 M1 H", (unsigned long)absPreheatHotendTemp);
|
SERIAL_ECHOPAIR(" M145 S1 H", (unsigned long)absPreheatHotendTemp);
|
||||||
SERIAL_ECHOPAIR(" B", (unsigned long)absPreheatHPBTemp);
|
SERIAL_ECHOPAIR(" B", (unsigned long)absPreheatHPBTemp);
|
||||||
SERIAL_ECHOPAIR(" F", (unsigned long)absPreheatFanSpeed);
|
SERIAL_ECHOPAIR(" F", (unsigned long)absPreheatFanSpeed);
|
||||||
SERIAL_EOL;
|
SERIAL_EOL;
|
||||||
|
|
|
@ -1,3 +1,25 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
#ifndef CONFIGURATION_STORE_H
|
#ifndef CONFIGURATION_STORE_H
|
||||||
#define CONFIGURATION_STORE_H
|
#define CONFIGURATION_STORE_H
|
||||||
|
|
||||||
|
|
|
@ -1 +0,0 @@
|
||||||
Header set Access-Control-Allow-Origin "*"
|
|
|
@ -1,64 +0,0 @@
|
||||||
#ifndef BOARDS_H
|
|
||||||
#define BOARDS_H
|
|
||||||
|
|
||||||
#define BOARD_UNKNOWN -1
|
|
||||||
|
|
||||||
#define BOARD_GEN7_CUSTOM 10 // Gen7 custom (Alfons3 Version) "https://github.com/Alfons3/Generation_7_Electronics"
|
|
||||||
#define BOARD_GEN7_12 11 // Gen7 v1.1, v1.2
|
|
||||||
#define BOARD_GEN7_13 12 // Gen7 v1.3
|
|
||||||
#define BOARD_GEN7_14 13 // Gen7 v1.4
|
|
||||||
#define BOARD_CHEAPTRONIC 2 // Cheaptronic v1.0
|
|
||||||
#define BOARD_SETHI 20 // Sethi 3D_1
|
|
||||||
#define BOARD_RAMPS_OLD 3 // MEGA/RAMPS up to 1.2
|
|
||||||
#define BOARD_RAMPS_13_EFB 33 // RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Bed)
|
|
||||||
#define BOARD_RAMPS_13_EEB 34 // RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Bed)
|
|
||||||
#define BOARD_RAMPS_13_EFF 35 // RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Fan)
|
|
||||||
#define BOARD_RAMPS_13_EEF 36 // RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Fan)
|
|
||||||
#define BOARD_RAMPS_13_SF 38 // RAMPS 1.3 / 1.4 (Power outputs: Spindle, Controller Fan)
|
|
||||||
#define BOARD_FELIX2 37 // Felix 2.0+ Electronics Board (RAMPS like)
|
|
||||||
#define BOARD_RIGIDBOARD 42 // Invent-A-Part RigidBoard
|
|
||||||
#define BOARD_GEN6 5 // Gen6
|
|
||||||
#define BOARD_GEN6_DELUXE 51 // Gen6 deluxe
|
|
||||||
#define BOARD_SANGUINOLOLU_11 6 // Sanguinololu < 1.2
|
|
||||||
#define BOARD_SANGUINOLOLU_12 62 // Sanguinololu 1.2 and above
|
|
||||||
#define BOARD_MELZI 63 // Melzi
|
|
||||||
#define BOARD_STB_11 64 // STB V1.1
|
|
||||||
#define BOARD_AZTEEG_X1 65 // Azteeg X1
|
|
||||||
#define BOARD_MELZI_MAKR3D 66 // Melzi with ATmega1284 (MaKr3d version)
|
|
||||||
#define BOARD_AZTEEG_X3 67 // Azteeg X3
|
|
||||||
#define BOARD_AZTEEG_X3_PRO 68 // Azteeg X3 Pro
|
|
||||||
#define BOARD_ULTIMAKER 7 // Ultimaker
|
|
||||||
#define BOARD_ULTIMAKER_OLD 71 // Ultimaker (Older electronics. Pre 1.5.4. This is rare)
|
|
||||||
#define BOARD_ULTIMAIN_2 72 // Ultimainboard 2.x (Uses TEMP_SENSOR 20)
|
|
||||||
#define BOARD_3DRAG 77 // 3Drag Controller
|
|
||||||
#define BOARD_K8200 78 // Vellemann K8200 Controller (derived from 3Drag Controller)
|
|
||||||
#define BOARD_TEENSYLU 8 // Teensylu
|
|
||||||
#define BOARD_RUMBA 80 // Rumba
|
|
||||||
#define BOARD_PRINTRBOARD 81 // Printrboard (AT90USB1286)
|
|
||||||
#define BOARD_BRAINWAVE 82 // Brainwave (AT90USB646)
|
|
||||||
#define BOARD_SAV_MKI 83 // SAV Mk-I (AT90USB1286)
|
|
||||||
#define BOARD_TEENSY2 84 // Teensy++2.0 (AT90USB1286) - CLI compile: DEFINES=AT90USBxx_TEENSYPP_ASSIGNMENTS HARDWARE_MOTHERBOARD=84 make
|
|
||||||
#define BOARD_BRAINWAVE_PRO 85 // Brainwave Pro (AT90USB1286)
|
|
||||||
#define BOARD_GEN3_PLUS 9 // Gen3+
|
|
||||||
#define BOARD_GEN3_MONOLITHIC 22 // Gen3 Monolithic Electronics
|
|
||||||
#define BOARD_MEGATRONICS 70 // Megatronics
|
|
||||||
#define BOARD_MEGATRONICS_2 701 // Megatronics v2.0
|
|
||||||
#define BOARD_MINITRONICS 702 // Minitronics v1.0/1.1
|
|
||||||
#define BOARD_MEGATRONICS_3 703 // Megatronics v3.0
|
|
||||||
#define BOARD_OMCA_A 90 // Alpha OMCA board
|
|
||||||
#define BOARD_OMCA 91 // Final OMCA board
|
|
||||||
#define BOARD_RAMBO 301 // Rambo
|
|
||||||
#define BOARD_MINIRAMBO 302 // Mini-Rambo
|
|
||||||
#define BOARD_MEGACONTROLLER 310 // Mega controller
|
|
||||||
#define BOARD_ELEFU_3 21 // Elefu Ra Board (v3)
|
|
||||||
#define BOARD_5DPRINT 88 // 5DPrint D8 Driver Board
|
|
||||||
#define BOARD_LEAPFROG 999 // Leapfrog
|
|
||||||
#define BOARD_MKS_BASE 40 // MKS BASE 1.0
|
|
||||||
#define BOARD_BAM_DICE 401 // 2PrintBeta BAM&DICE with STK drivers
|
|
||||||
#define BOARD_BAM_DICE_DUE 402 // 2PrintBeta BAM&DICE Due with STK drivers
|
|
||||||
|
|
||||||
#define BOARD_99 99 // This is in pins.h but...?
|
|
||||||
|
|
||||||
#define MB(board) (MOTHERBOARD==BOARD_##board)
|
|
||||||
|
|
||||||
#endif //__BOARDS_H
|
|
|
@ -1,228 +0,0 @@
|
||||||
#ifndef LANGUAGE_H
|
|
||||||
#define LANGUAGE_H
|
|
||||||
|
|
||||||
#include "Configuration.h"
|
|
||||||
|
|
||||||
#define LANGUAGE_CONCAT(M) #M
|
|
||||||
#define GENERATE_LANGUAGE_INCLUDE(M) LANGUAGE_CONCAT(language_##M.h)
|
|
||||||
|
|
||||||
|
|
||||||
// NOTE: IF YOU CHANGE LANGUAGE FILES OR MERGE A FILE WITH CHANGES
|
|
||||||
//
|
|
||||||
// ==> ALWAYS TRY TO COMPILE MARLIN WITH/WITHOUT "ULTIPANEL" / "ULTRALCD" / "SDSUPPORT" #define IN "Configuration.h"
|
|
||||||
// ==> ALSO TRY ALL AVAILABLE LANGUAGE OPTIONS
|
|
||||||
// See also documentation/LCDLanguageFont.md
|
|
||||||
|
|
||||||
// Languages
|
|
||||||
// en English
|
|
||||||
// pl Polish
|
|
||||||
// fr French
|
|
||||||
// de German
|
|
||||||
// es Spanish
|
|
||||||
// ru Russian
|
|
||||||
// bg Bulgarian
|
|
||||||
// it Italian
|
|
||||||
// pt Portuguese
|
|
||||||
// pt-br Portuguese (Brazil)
|
|
||||||
// fi Finnish
|
|
||||||
// an Aragonese
|
|
||||||
// nl Dutch
|
|
||||||
// ca Catalan
|
|
||||||
// eu Basque-Euskera
|
|
||||||
// kana Japanese
|
|
||||||
// kana_utf Japanese
|
|
||||||
// cn Chinese
|
|
||||||
|
|
||||||
// fallback if no language is set, don't change
|
|
||||||
#ifndef LANGUAGE_INCLUDE
|
|
||||||
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if ENABLED(USE_AUTOMATIC_VERSIONING)
|
|
||||||
#include "_Version.h"
|
|
||||||
#else
|
|
||||||
#include "Default_Version.h"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define PROTOCOL_VERSION "1.0"
|
|
||||||
|
|
||||||
#if MB(ULTIMAKER)|| MB(ULTIMAKER_OLD)|| MB(ULTIMAIN_2)
|
|
||||||
#define MACHINE_NAME "Ultimaker"
|
|
||||||
#define SOURCE_CODE_URL "https://github.com/Ultimaker/Marlin"
|
|
||||||
#elif MB(RUMBA)
|
|
||||||
#define MACHINE_NAME "Rumba"
|
|
||||||
#elif MB(3DRAG)
|
|
||||||
#define MACHINE_NAME "3Drag"
|
|
||||||
#define SOURCE_CODE_URL "http://3dprint.elettronicain.it/"
|
|
||||||
#elif MB(K8200)
|
|
||||||
#define MACHINE_NAME "K8200"
|
|
||||||
#define SOURCE_CODE_URL "https://github.com/CONSULitAS/Marlin-K8200"
|
|
||||||
#elif MB(5DPRINT)
|
|
||||||
#define MACHINE_NAME "Makibox"
|
|
||||||
#elif MB(SAV_MKI)
|
|
||||||
#define MACHINE_NAME "SAV MkI"
|
|
||||||
#define SOURCE_CODE_URL "https://github.com/fmalpartida/Marlin/tree/SAV-MkI-config"
|
|
||||||
#elif !defined(MACHINE_NAME)
|
|
||||||
#define MACHINE_NAME "3D Printer"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef CUSTOM_MACHINE_NAME
|
|
||||||
#undef MACHINE_NAME
|
|
||||||
#define MACHINE_NAME CUSTOM_MACHINE_NAME
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef SOURCE_CODE_URL
|
|
||||||
#define SOURCE_CODE_URL "https://github.com/MarlinFirmware/Marlin"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef DETAILED_BUILD_VERSION
|
|
||||||
#error BUILD_VERSION Information must be specified
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef MACHINE_UUID
|
|
||||||
#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
#define STRINGIFY_(n) #n
|
|
||||||
#define STRINGIFY(n) STRINGIFY_(n)
|
|
||||||
|
|
||||||
|
|
||||||
// Common LCD messages
|
|
||||||
|
|
||||||
/* nothing here yet */
|
|
||||||
|
|
||||||
// Common serial messages
|
|
||||||
#define MSG_MARLIN "Marlin"
|
|
||||||
|
|
||||||
// Serial Console Messages (do not translate those!)
|
|
||||||
|
|
||||||
#define MSG_Enqueueing "enqueueing \""
|
|
||||||
#define MSG_POWERUP "PowerUp"
|
|
||||||
#define MSG_EXTERNAL_RESET " External Reset"
|
|
||||||
#define MSG_BROWNOUT_RESET " Brown out Reset"
|
|
||||||
#define MSG_WATCHDOG_RESET " Watchdog Reset"
|
|
||||||
#define MSG_SOFTWARE_RESET " Software Reset"
|
|
||||||
#define MSG_AUTHOR " | Author: "
|
|
||||||
#define MSG_CONFIGURATION_VER " Last Updated: "
|
|
||||||
#define MSG_FREE_MEMORY " Free Memory: "
|
|
||||||
#define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
|
||||||
#define MSG_OK "ok"
|
|
||||||
#define MSG_WAIT "wait"
|
|
||||||
#define MSG_FILE_SAVED "Done saving file."
|
|
||||||
#define MSG_ERR_LINE_NO "Line Number is not Last Line Number+1, Last Line: "
|
|
||||||
#define MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
|
||||||
#define MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
|
||||||
#define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM "No Line Number with checksum, Last Line: "
|
|
||||||
#define MSG_FILE_PRINTED "Done printing file"
|
|
||||||
#define MSG_BEGIN_FILE_LIST "Begin file list"
|
|
||||||
#define MSG_END_FILE_LIST "End file list"
|
|
||||||
#define MSG_INVALID_EXTRUDER "Invalid extruder"
|
|
||||||
#define MSG_INVALID_SOLENOID "Invalid solenoid"
|
|
||||||
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
|
||||||
#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"
|
|
||||||
#define MSG_COUNT_X " Count X: "
|
|
||||||
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
|
||||||
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
|
||||||
#define MSG_RESEND "Resend: "
|
|
||||||
#define MSG_UNKNOWN_COMMAND "Unknown command: \""
|
|
||||||
#define MSG_ACTIVE_EXTRUDER "Active Extruder: "
|
|
||||||
#define MSG_X_MIN "x_min: "
|
|
||||||
#define MSG_X_MAX "x_max: "
|
|
||||||
#define MSG_Y_MIN "y_min: "
|
|
||||||
#define MSG_Y_MAX "y_max: "
|
|
||||||
#define MSG_Z_MIN "z_min: "
|
|
||||||
#define MSG_Z_MAX "z_max: "
|
|
||||||
#define MSG_Z2_MAX "z2_max: "
|
|
||||||
#define MSG_Z_PROBE "z_probe: "
|
|
||||||
#define MSG_ERR_MATERIAL_INDEX "M145 S<index> out of range (0-1)"
|
|
||||||
#define MSG_ERR_M421_REQUIRES_XYZ "M421 requires XYZ parameters"
|
|
||||||
#define MSG_ERR_MESH_INDEX_OOB "Mesh XY index is out of bounds"
|
|
||||||
#define MSG_ERR_M428_TOO_FAR "Too far from reference point"
|
|
||||||
#define MSG_M119_REPORT "Reporting endstop status"
|
|
||||||
#define MSG_ENDSTOP_HIT "TRIGGERED"
|
|
||||||
#define MSG_ENDSTOP_OPEN "open"
|
|
||||||
#define MSG_HOTEND_OFFSET "Hotend offsets:"
|
|
||||||
|
|
||||||
#define MSG_SD_CANT_OPEN_SUBDIR "Cannot open subdir"
|
|
||||||
#define MSG_SD_INIT_FAIL "SD init fail"
|
|
||||||
#define MSG_SD_VOL_INIT_FAIL "volume.init failed"
|
|
||||||
#define MSG_SD_OPENROOT_FAIL "openRoot failed"
|
|
||||||
#define MSG_SD_CARD_OK "SD card ok"
|
|
||||||
#define MSG_SD_WORKDIR_FAIL "workDir open failed"
|
|
||||||
#define MSG_SD_OPEN_FILE_FAIL "open failed, File: "
|
|
||||||
#define MSG_SD_FILE_OPENED "File opened: "
|
|
||||||
#define MSG_SD_SIZE " Size: "
|
|
||||||
#define MSG_SD_FILE_SELECTED "File selected"
|
|
||||||
#define MSG_SD_WRITE_TO_FILE "Writing to file: "
|
|
||||||
#define MSG_SD_PRINTING_BYTE "SD printing byte "
|
|
||||||
#define MSG_SD_NOT_PRINTING "Not SD printing"
|
|
||||||
#define MSG_SD_ERR_WRITE_TO_FILE "error writing to file"
|
|
||||||
#define MSG_SD_CANT_ENTER_SUBDIR "Cannot enter subdir: "
|
|
||||||
|
|
||||||
#define MSG_STEPPER_TOO_HIGH "Steprate too high: "
|
|
||||||
#define MSG_ENDSTOPS_HIT "endstops hit: "
|
|
||||||
#define MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
|
||||||
#define MSG_ERR_LONG_EXTRUDE_STOP " too long extrusion prevented"
|
|
||||||
#define MSG_TOO_COLD_FOR_M600 "M600 Hotend too cold to change filament"
|
|
||||||
#define MSG_BABYSTEPPING_X "Babystepping X"
|
|
||||||
#define MSG_BABYSTEPPING_Y "Babystepping Y"
|
|
||||||
#define MSG_BABYSTEPPING_Z "Babystepping Z"
|
|
||||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
|
|
||||||
|
|
||||||
#define MSG_ERR_EEPROM_WRITE "Error writing to EEPROM!"
|
|
||||||
|
|
||||||
// temperature.cpp strings
|
|
||||||
#define MSG_PID_AUTOTUNE "PID Autotune"
|
|
||||||
#define MSG_PID_AUTOTUNE_START MSG_PID_AUTOTUNE " start"
|
|
||||||
#define MSG_PID_AUTOTUNE_FAILED MSG_PID_AUTOTUNE " failed!"
|
|
||||||
#define MSG_PID_BAD_EXTRUDER_NUM MSG_PID_AUTOTUNE_FAILED " Bad extruder number"
|
|
||||||
#define MSG_PID_TEMP_TOO_HIGH MSG_PID_AUTOTUNE_FAILED " Temperature too high"
|
|
||||||
#define MSG_PID_TIMEOUT MSG_PID_AUTOTUNE_FAILED " timeout"
|
|
||||||
#define MSG_BIAS " bias: "
|
|
||||||
#define MSG_D " d: "
|
|
||||||
#define MSG_T_MIN " min: "
|
|
||||||
#define MSG_T_MAX " max: "
|
|
||||||
#define MSG_KU " Ku: "
|
|
||||||
#define MSG_TU " Tu: "
|
|
||||||
#define MSG_CLASSIC_PID " Classic PID "
|
|
||||||
#define MSG_KP " Kp: "
|
|
||||||
#define MSG_KI " Ki: "
|
|
||||||
#define MSG_KD " Kd: "
|
|
||||||
#define MSG_B "B:"
|
|
||||||
#define MSG_T "T:"
|
|
||||||
#define MSG_AT " @:"
|
|
||||||
#define MSG_PID_AUTOTUNE_FINISHED MSG_PID_AUTOTUNE " finished! Put the last Kp, Ki and Kd constants from below into Configuration.h"
|
|
||||||
#define MSG_PID_DEBUG " PID_DEBUG "
|
|
||||||
#define MSG_PID_DEBUG_INPUT ": Input "
|
|
||||||
#define MSG_PID_DEBUG_OUTPUT " Output "
|
|
||||||
#define MSG_PID_DEBUG_PTERM " pTerm "
|
|
||||||
#define MSG_PID_DEBUG_ITERM " iTerm "
|
|
||||||
#define MSG_PID_DEBUG_DTERM " dTerm "
|
|
||||||
#define MSG_PID_DEBUG_CTERM " cTerm "
|
|
||||||
#define MSG_INVALID_EXTRUDER_NUM " - Invalid extruder number !"
|
|
||||||
|
|
||||||
#define MSG_HEATER_BED "bed"
|
|
||||||
#define MSG_STOPPED_HEATER ", system stopped! Heater_ID: "
|
|
||||||
#define MSG_REDUNDANCY "Heater switched off. Temperature difference between temp sensors is too high !"
|
|
||||||
#define MSG_T_HEATING_FAILED "Heating failed"
|
|
||||||
#define MSG_T_THERMAL_RUNAWAY "Thermal Runaway"
|
|
||||||
#define MSG_T_MAXTEMP "MAXTEMP triggered"
|
|
||||||
#define MSG_T_MINTEMP "MINTEMP triggered"
|
|
||||||
|
|
||||||
// Debug
|
|
||||||
#define MSG_DEBUG_ECHO "DEBUG ECHO ENABLED"
|
|
||||||
#define MSG_DEBUG_INFO "DEBUG INFO ENABLED"
|
|
||||||
#define MSG_DEBUG_ERRORS "DEBUG ERRORS ENABLED"
|
|
||||||
#define MSG_DEBUG_DRYRUN "DEBUG DRYRUN ENABLED"
|
|
||||||
|
|
||||||
// LCD Menu Messages
|
|
||||||
|
|
||||||
#if DISABLED(DISPLAY_CHARSET_HD44780_JAPAN) && DISABLED(DISPLAY_CHARSET_HD44780_WESTERN) && DISABLED(DISPLAY_CHARSET_HD44780_CYRILLIC)
|
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include LANGUAGE_INCLUDE
|
|
||||||
#include "language_en.h"
|
|
||||||
|
|
||||||
#endif //__LANGUAGE_H
|
|
|
@ -1,344 +0,0 @@
|
||||||
/* configurator.css */
|
|
||||||
/* Styles for Marlin Configurator */
|
|
||||||
|
|
||||||
.clear { clear: both; }
|
|
||||||
|
|
||||||
/* Prevent selection except PRE tags */
|
|
||||||
* {
|
|
||||||
-webkit-touch-callout: none;
|
|
||||||
-webkit-user-select: none;
|
|
||||||
-khtml-user-select: none;
|
|
||||||
-moz-user-select: none;
|
|
||||||
-ms-user-select: none;
|
|
||||||
user-select: none;
|
|
||||||
}
|
|
||||||
pre {
|
|
||||||
-webkit-touch-callout: text;
|
|
||||||
-webkit-user-select: text;
|
|
||||||
-khtml-user-select: text;
|
|
||||||
-moz-user-select: text;
|
|
||||||
-ms-user-select: text;
|
|
||||||
user-select: text;
|
|
||||||
}
|
|
||||||
|
|
||||||
body { margin: 0; padding: 0; background: #56A; color: #000; font-family: monospace; }
|
|
||||||
#main {
|
|
||||||
max-width: 1100px;
|
|
||||||
margin: 0 auto 10px;
|
|
||||||
padding: 0 2%; width: 96%;
|
|
||||||
}
|
|
||||||
|
|
||||||
h1, h2, h3, h4, h5, h6 { clear: both; }
|
|
||||||
|
|
||||||
h1, p.info { font-family: sans-serif; }
|
|
||||||
h1 {
|
|
||||||
height: 38px;
|
|
||||||
margin-bottom: -30px;
|
|
||||||
color: #FFF;
|
|
||||||
background: transparent url(logo.png) right top no-repeat;
|
|
||||||
}
|
|
||||||
p.info { padding: 0; color: #000; }
|
|
||||||
p.info span { color: #800; }
|
|
||||||
|
|
||||||
#message { text-align: center; }
|
|
||||||
#message { width: 80%; margin: 0 auto 0.25em; color: #FF0; }
|
|
||||||
#message p { padding: 2px 0; font-weight: bold; border-radius: 0.8em; }
|
|
||||||
#message p.message { color: #080; background: #CFC; }
|
|
||||||
#message p.error { color: #F00; background: #FF4; }
|
|
||||||
#message p.warning { color: #FF0; background: #BA4; }
|
|
||||||
#message p.message span,
|
|
||||||
#message p.error span,
|
|
||||||
#message p.warning span {
|
|
||||||
color: #A00;
|
|
||||||
background: rgba(255, 255, 255, 1);
|
|
||||||
border: 1px solid rgba(0,0,0,0.5);
|
|
||||||
border-radius: 1em;
|
|
||||||
float: right;
|
|
||||||
margin-right: 0.5em;
|
|
||||||
padding: 0 3px;
|
|
||||||
font-family: sans-serif;
|
|
||||||
font-size: small;
|
|
||||||
position: relative;
|
|
||||||
top: -1px;
|
|
||||||
}
|
|
||||||
|
|
||||||
#help strong { color: #0DD; }
|
|
||||||
img { display: none; }
|
|
||||||
|
|
||||||
/* Forms */
|
|
||||||
|
|
||||||
#config_form {
|
|
||||||
display: block;
|
|
||||||
background: #EEE;
|
|
||||||
padding: 6px 20px 20px;
|
|
||||||
color: #000;
|
|
||||||
position: relative;
|
|
||||||
border-radius: 1.5em;
|
|
||||||
border-top-left-radius: 0;
|
|
||||||
}
|
|
||||||
fieldset {
|
|
||||||
height: 16.1em;
|
|
||||||
overflow-y: scroll;
|
|
||||||
overflow-x: hidden;
|
|
||||||
margin-top: 10px;
|
|
||||||
}
|
|
||||||
label, input, select, textarea { display: block; float: left; margin: 1px 0; }
|
|
||||||
label.newline, textarea, fieldset { clear: both; }
|
|
||||||
label {
|
|
||||||
width: 120px; /* label area */
|
|
||||||
height: 1em;
|
|
||||||
padding: 10px 460px 10px 1em;
|
|
||||||
margin-right: -450px;
|
|
||||||
text-align: right;
|
|
||||||
}
|
|
||||||
label.blocked, label.added.blocked, label.added.blocked.sublabel { color: #AAA; }
|
|
||||||
|
|
||||||
label.added.sublabel {
|
|
||||||
width: auto;
|
|
||||||
margin: 11px -2.5em 0 1em;
|
|
||||||
padding: 0 3em 0 0;
|
|
||||||
font-style: italic;
|
|
||||||
color: #444;
|
|
||||||
}
|
|
||||||
label+label.added.sublabel {
|
|
||||||
margin-left: 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
input[type="text"], select { margin: 0.75em 0 0; }
|
|
||||||
input[type="checkbox"], input[type="radio"], input[type="file"] { margin: 1em 0 0; }
|
|
||||||
input[type="checkbox"].enabler, input[type="radio"].enabler { margin-left: 1em; }
|
|
||||||
|
|
||||||
input:disabled { color: #BBB; }
|
|
||||||
|
|
||||||
#config_form input[type="text"].subitem { width: 4em; }
|
|
||||||
#config_form input[type="text"].subitem+.subitem { margin-left: 4px; }
|
|
||||||
|
|
||||||
input[type="text"].added { width: 20em; }
|
|
||||||
label.added {
|
|
||||||
width: 265px; /* label area */
|
|
||||||
height: 1em;
|
|
||||||
padding: 10px 370px 10px 1em;
|
|
||||||
margin-right: -360px;
|
|
||||||
text-align: right;
|
|
||||||
}
|
|
||||||
|
|
||||||
ul.tabs { padding: 0; list-style: none; }
|
|
||||||
ul.tabs li { display: inline; }
|
|
||||||
ul.tabs li a,
|
|
||||||
ul.tabs li a.active:hover,
|
|
||||||
ul.tabs li a.active:active {
|
|
||||||
display: block;
|
|
||||||
float: left;
|
|
||||||
background: #1E4059;
|
|
||||||
color: #CCC;
|
|
||||||
font-size: 110%;
|
|
||||||
border-radius: 0.25em 0.25em 0 0;
|
|
||||||
margin: 0 4px 0 0;
|
|
||||||
padding: 2px 8px;
|
|
||||||
text-decoration: none;
|
|
||||||
font-family: georgia,"times new roman",times;
|
|
||||||
}
|
|
||||||
ul.tabs li a.active:link,
|
|
||||||
ul.tabs li a.active:visited {
|
|
||||||
background: #DDD;
|
|
||||||
color: #06F;
|
|
||||||
cursor: default;
|
|
||||||
margin-top: -4px;
|
|
||||||
padding-bottom: 4px;
|
|
||||||
padding-top: 4px;
|
|
||||||
}
|
|
||||||
ul.tabs li a:hover,
|
|
||||||
ul.tabs li a:active {
|
|
||||||
background: #000;
|
|
||||||
color: #FFF;
|
|
||||||
}
|
|
||||||
|
|
||||||
fieldset { display: none; border: 1px solid #AAA; border-radius: 1em; }
|
|
||||||
fieldset legend { display: none; }
|
|
||||||
|
|
||||||
.hilightable span {
|
|
||||||
display: block;
|
|
||||||
float: left;
|
|
||||||
width: 100%;
|
|
||||||
height: 1.3em;
|
|
||||||
background: rgba(225,255,0,1);
|
|
||||||
margin: 0 -100% -1em 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
#serial_stepper { padding-top: 0.75em; display: block; float: left; }
|
|
||||||
/*#SERIAL_PORT { display: none; }*/
|
|
||||||
|
|
||||||
/* Tooltips */
|
|
||||||
|
|
||||||
#tooltip {
|
|
||||||
display: none;
|
|
||||||
max-width: 30em;
|
|
||||||
padding: 8px;
|
|
||||||
border: 2px solid #73d699;
|
|
||||||
border-radius: 1em;
|
|
||||||
position: absolute;
|
|
||||||
z-index: 999;
|
|
||||||
font-family: sans-serif;
|
|
||||||
font-size: 85%;
|
|
||||||
color: #000;
|
|
||||||
line-height: 1.1;
|
|
||||||
background: #e2ff99; /* Old browsers */
|
|
||||||
background: -moz-linear-gradient(top, #e2ff99 0%, #73d699 100%); /* FF3.6+ */
|
|
||||||
background: -webkit-gradient(linear, left top, left bottom, color-stop(0%,#e2ff99), color-stop(100%,#73d699)); /* Chrome,Safari4+ */
|
|
||||||
background: -webkit-linear-gradient(top, #e2ff99 0%,#73d699 100%); /* Chrome10+,Safari5.1+ */
|
|
||||||
background: -o-linear-gradient(top, #e2ff99 0%,#73d699 100%); /* Opera 11.10+ */
|
|
||||||
background: -ms-linear-gradient(top, #e2ff99 0%,#73d699 100%); /* IE10+ */
|
|
||||||
background: linear-gradient(to bottom, #e2ff99 0%,#73d699 100%); /* W3C */
|
|
||||||
filter: progid:DXImageTransform.Microsoft.gradient( startColorstr='#e2ff99', endColorstr='#73d699',GradientType=0 ); /* IE6-9 */
|
|
||||||
-webkit-box-shadow: 0px 6px 25px -4px rgba(0,0,0,0.75);
|
|
||||||
-moz-box-shadow: 0px 6px 25px -4px rgba(0,0,0,0.75);
|
|
||||||
box-shadow: 0px 6px 25px -4px rgba(0,0,0,0.75);
|
|
||||||
}
|
|
||||||
#tooltip>span {
|
|
||||||
position: absolute;
|
|
||||||
content: "";
|
|
||||||
width: 0;
|
|
||||||
height: 0;
|
|
||||||
border-left: 8px solid transparent;
|
|
||||||
border-right: 8px solid transparent;
|
|
||||||
border-top: 8px solid #73d699;
|
|
||||||
z-index: 999;
|
|
||||||
bottom: -10px;
|
|
||||||
left: 20px;
|
|
||||||
}
|
|
||||||
#tooltip>strong { color: #00B; }
|
|
||||||
|
|
||||||
/* Tooltips Checkbox */
|
|
||||||
|
|
||||||
#tipson {
|
|
||||||
width: auto;
|
|
||||||
height: auto;
|
|
||||||
padding: 0;
|
|
||||||
margin-right: 0;
|
|
||||||
float: right;
|
|
||||||
font-weight: bold;
|
|
||||||
font-size: 100%;
|
|
||||||
font-family: helvetica;
|
|
||||||
text-align: left;
|
|
||||||
cursor: pointer;
|
|
||||||
}
|
|
||||||
#tipson input { float: none; display: inline; cursor: pointer; }
|
|
||||||
|
|
||||||
/* Config Text */
|
|
||||||
|
|
||||||
pre.config {
|
|
||||||
height: 25em;
|
|
||||||
padding: 10px;
|
|
||||||
border: 2px solid #888;
|
|
||||||
border-radius: 5px;
|
|
||||||
overflow: auto;
|
|
||||||
clear: both;
|
|
||||||
background-color: #FFF;
|
|
||||||
color: #000;
|
|
||||||
font-family: "Fira Mono", monospace;
|
|
||||||
font-size: small;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Pre Headers */
|
|
||||||
|
|
||||||
h2 {
|
|
||||||
width: 100%;
|
|
||||||
margin: 12px -300px 4px 0;
|
|
||||||
padding: 0;
|
|
||||||
float: left;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Disclosure Widget */
|
|
||||||
|
|
||||||
span.disclose, a.download, a.download-all {︎
|
|
||||||
display: block;
|
|
||||||
float: right;
|
|
||||||
margin-top: 12px;
|
|
||||||
}
|
|
||||||
|
|
||||||
span.disclose {
|
|
||||||
margin-right: -10px; /* total width */
|
|
||||||
margin-left: 14px;
|
|
||||||
width: 0;
|
|
||||||
height: 0;
|
|
||||||
position: relative;
|
|
||||||
left: 3px;
|
|
||||||
top: 3px;
|
|
||||||
cursor: pointer;
|
|
||||||
border-left: 8px solid transparent;
|
|
||||||
border-right: 8px solid transparent;
|
|
||||||
border-top: 10px solid #000;
|
|
||||||
}
|
|
||||||
span.disclose.closed {
|
|
||||||
margin-right: -8px; /* total width */
|
|
||||||
margin-left: 10px;
|
|
||||||
left: 0;
|
|
||||||
top: 0;
|
|
||||||
border-top: 8px solid transparent;
|
|
||||||
border-bottom: 8px solid transparent;
|
|
||||||
border-right: 10px solid #000;
|
|
||||||
}
|
|
||||||
span.disclose.almost {
|
|
||||||
-ms-transform: rotate(45deg); /* IE 9 */
|
|
||||||
-webkit-transform: rotate(45deg); /* Chrome, Safari, Opera */
|
|
||||||
transform: rotate(45deg);
|
|
||||||
}
|
|
||||||
span.disclose.closed.almost {
|
|
||||||
left: 1px;
|
|
||||||
top: 3px;
|
|
||||||
-ms-transform: rotate(315deg); /* IE 9 */
|
|
||||||
-webkit-transform: rotate(315deg); /* Chrome, Safari, Opera */
|
|
||||||
transform: rotate(315deg);
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Download Button */
|
|
||||||
|
|
||||||
a.download, a.download-all {
|
|
||||||
visibility: hidden;
|
|
||||||
padding: 2px;
|
|
||||||
border: 1px solid #494;
|
|
||||||
border-radius: 4px;
|
|
||||||
margin: 12px 0 0;
|
|
||||||
background: #FFF;
|
|
||||||
color: #494;
|
|
||||||
font-family: sans-serif;
|
|
||||||
font-size: small;
|
|
||||||
font-weight: bold;
|
|
||||||
text-decoration: none;
|
|
||||||
}
|
|
||||||
a.download-all { margin: 9px 2em 0; color: #449; border-color: #449; }
|
|
||||||
|
|
||||||
input[type="text"].one_of_2 { max-width: 15%; }
|
|
||||||
input[type="text"].one_of_3 { max-width: 10%; }
|
|
||||||
input[type="text"].one_of_4 { max-width: 7%; }
|
|
||||||
|
|
||||||
select.one_of_2 { max-width: 15%; }
|
|
||||||
select.one_of_3 { max-width: 10%; }
|
|
||||||
select.one_of_4 { max-width: 14%; }
|
|
||||||
select.one_of_4+span.label+select.one_of_4+span.label { clear: both; margin-left: 265px; padding-left: 1.75em; }
|
|
||||||
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; }
|
|
||||||
|
|
||||||
@media all and (min-width: 1140px) {
|
|
||||||
|
|
||||||
#main { max-width: 10000px; }
|
|
||||||
|
|
||||||
fieldset { float: left; width: 50%; height: auto; }
|
|
||||||
|
|
||||||
#config_text, #config_adv_text { float: right; clear: right; width: 45%; }
|
|
||||||
|
|
||||||
pre.config { height: 20em; }
|
|
||||||
|
|
||||||
.disclose { display: none; }
|
|
||||||
|
|
||||||
input[type="text"].one_of_2 { max-width: 15%; }
|
|
||||||
input[type="text"].one_of_3 { max-width: 9%; }
|
|
||||||
input[type="text"].one_of_4 { max-width: 8%; }
|
|
||||||
|
|
||||||
select.one_of_2 { max-width: 15%; }
|
|
||||||
select.one_of_3 { max-width: 10%; }
|
|
||||||
select.one_of_4 { max-width: 16%; }
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
/*label.blocked, .blocked { display: none; }*/
|
|
||||||
|
|
Binary file not shown.
Before Width: | Height: | Size: 1.2 KiB |
|
@ -1,129 +0,0 @@
|
||||||
<!DOCTYPE html>
|
|
||||||
<html>
|
|
||||||
<head>
|
|
||||||
<meta charset="UTF-8">
|
|
||||||
<title>Marlin Firmware Configurator</title>
|
|
||||||
<link href='http://fonts.googleapis.com/css?family=Fira+Mono&subset=latin,latin-ext' rel='stylesheet' type='text/css' />
|
|
||||||
<script src="js/jquery-2.1.3.min.js"></script>
|
|
||||||
<script src="js/binarystring.js"></script>
|
|
||||||
<script src="js/binaryfileuploader.js"></script>
|
|
||||||
<script src="js/FileSaver.min.js"></script>
|
|
||||||
<script src="js/jszip.min.js"></script>
|
|
||||||
<script src="js/jcanvas.js"></script>
|
|
||||||
<script src="js/jstepper.js"></script>
|
|
||||||
<script src="js/configurator.js"></script>
|
|
||||||
<link rel="stylesheet" href="css/configurator.css" type="text/css" media="all" />
|
|
||||||
</head>
|
|
||||||
<body>
|
|
||||||
<section id="main">
|
|
||||||
<h1>Marlin Configurator</h1>
|
|
||||||
<p class="info">Select presets (coming soon), modify, and download.</p>
|
|
||||||
|
|
||||||
<div id="message"></div>
|
|
||||||
<div id="tabs"></div>
|
|
||||||
|
|
||||||
<form id="config_form">
|
|
||||||
|
|
||||||
<div id="tooltip"></div>
|
|
||||||
|
|
||||||
<label>Drop Files:</label><input type="file" id="file-upload" />
|
|
||||||
<label id="tipson"><input type="checkbox" checked /> ?</label>
|
|
||||||
<a href="" class="download-all">Download Zip</a>
|
|
||||||
|
|
||||||
<fieldset id="info">
|
|
||||||
<legend>Info</legend>
|
|
||||||
</fieldset>
|
|
||||||
|
|
||||||
<fieldset id="machine">
|
|
||||||
<legend>Machine</legend>
|
|
||||||
|
|
||||||
<label class="newline">Serial Port:</label><select name="SERIAL_PORT"></select><div id="serial_stepper"></div>
|
|
||||||
|
|
||||||
<label>Baud Rate:</label><select name="BAUDRATE"></select>
|
|
||||||
|
|
||||||
<label>AT90USB BT IF:</label>
|
|
||||||
<input name="BLUETOOTH" type="checkbox" value="1" checked />
|
|
||||||
|
|
||||||
<label class="newline">Motherboard:</label><select name="MOTHERBOARD"></select>
|
|
||||||
|
|
||||||
<label class="newline">Custom Name:</label><input name="CUSTOM_MACHINE_NAME" type="text" size="14" maxlength="12" value="" />
|
|
||||||
|
|
||||||
<label class="newline">Machine UUID:</label><input name="MACHINE_UUID" type="text" size="38" maxlength="36" value="" />
|
|
||||||
|
|
||||||
<label class="newline">Extruders:</label><select name="EXTRUDERS"></select>
|
|
||||||
|
|
||||||
<label class="newline">Power Supply:</label><select name="POWER_SUPPLY"></select>
|
|
||||||
|
|
||||||
<label>PS Default Off:</label>
|
|
||||||
<input name="PS_DEFAULT_OFF" type="checkbox" value="1" checked />
|
|
||||||
</fieldset>
|
|
||||||
|
|
||||||
<fieldset id="homing">
|
|
||||||
<legend>Homing</legend>
|
|
||||||
</fieldset>
|
|
||||||
|
|
||||||
<fieldset id="temperature">
|
|
||||||
<legend>Temperature</legend>
|
|
||||||
<label class="newline">Temp Sensor 0:</label><select name="TEMP_SENSOR_0"></select>
|
|
||||||
<label class="newline">Temp Sensor 1:</label><select name="TEMP_SENSOR_1"></select>
|
|
||||||
<label class="newline">Temp Sensor 2:</label><select name="TEMP_SENSOR_2"></select>
|
|
||||||
<label class="newline">Bed Temp Sensor:</label><select name="TEMP_SENSOR_BED"></select>
|
|
||||||
|
|
||||||
<label>Max Diff:</label>
|
|
||||||
<input name="MAX_REDUNDANT_TEMP_SENSOR_DIFF" type="text" size="3" maxlength="2" />
|
|
||||||
|
|
||||||
<label>Temp Residency Time (s):</label>
|
|
||||||
<input name="TEMP_RESIDENCY_TIME" type="text" size="3" maxlength="2" />
|
|
||||||
</fieldset>
|
|
||||||
|
|
||||||
<fieldset id="extruder">
|
|
||||||
<legend>Extruder</legend>
|
|
||||||
</fieldset>
|
|
||||||
|
|
||||||
<fieldset id="lcd">
|
|
||||||
<legend>LCD / SD</legend>
|
|
||||||
</fieldset>
|
|
||||||
|
|
||||||
<fieldset id="bedlevel">
|
|
||||||
<legend>Bed Leveling</legend>
|
|
||||||
</fieldset>
|
|
||||||
|
|
||||||
<fieldset id="fwretract">
|
|
||||||
<legend>FW Retract</legend>
|
|
||||||
</fieldset>
|
|
||||||
|
|
||||||
<fieldset id="tmc">
|
|
||||||
<legend>TMC</legend>
|
|
||||||
</fieldset>
|
|
||||||
|
|
||||||
<fieldset id="l6470">
|
|
||||||
<legend>L6470</legend>
|
|
||||||
</fieldset>
|
|
||||||
|
|
||||||
<fieldset id="extras">
|
|
||||||
<legend>Extras</legend>
|
|
||||||
</fieldset>
|
|
||||||
|
|
||||||
<fieldset id="more">
|
|
||||||
<legend>More…</legend>
|
|
||||||
</fieldset>
|
|
||||||
|
|
||||||
<section id="config_text">
|
|
||||||
<h2>Configuration.h</h2>
|
|
||||||
<span class="disclose"></span>
|
|
||||||
<a href="" class="download">Download</a>
|
|
||||||
<pre class="hilightable config"></pre>
|
|
||||||
</section>
|
|
||||||
|
|
||||||
<section id="config_adv_text">
|
|
||||||
<h2>Configuration_adv.h</h2>
|
|
||||||
<span class="disclose"></span>
|
|
||||||
<a href="" class="download">Download</a>
|
|
||||||
<pre class="hilightable config"></pre>
|
|
||||||
</section>
|
|
||||||
|
|
||||||
<br class="clear" />
|
|
||||||
</form>
|
|
||||||
</section>
|
|
||||||
</body>
|
|
||||||
</html>
|
|
2
Marlin/configurator/js/FileSaver.min.js
vendored
2
Marlin/configurator/js/FileSaver.min.js
vendored
|
@ -1,2 +0,0 @@
|
||||||
/*! @source http://purl.eligrey.com/github/FileSaver.js/blob/master/FileSaver.js */
|
|
||||||
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})}
|
|
|
@ -1,79 +0,0 @@
|
||||||
function BinaryFileUploader(o) {
|
|
||||||
this.options = null;
|
|
||||||
|
|
||||||
|
|
||||||
this._defaultOptions = {
|
|
||||||
element: null, // HTML file element
|
|
||||||
onFileLoad: function(file) {
|
|
||||||
console.log(file.toString());
|
|
||||||
}
|
|
||||||
};
|
|
||||||
|
|
||||||
|
|
||||||
this._init = function(o) {
|
|
||||||
if (!this.hasFileUploaderSupport()) return;
|
|
||||||
|
|
||||||
this._verifyDependencies();
|
|
||||||
|
|
||||||
this.options = this._mergeObjects(this._defaultOptions, o);
|
|
||||||
this._verifyOptions();
|
|
||||||
|
|
||||||
this.addFileChangeListener();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
this.hasFileUploaderSupport = function() {
|
|
||||||
return !!(window.File && window.FileReader && window.FileList && window.Blob);
|
|
||||||
}
|
|
||||||
|
|
||||||
this.addFileChangeListener = function() {
|
|
||||||
this.options.element.addEventListener(
|
|
||||||
'change',
|
|
||||||
this._bind(this, this.onFileChange)
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
this.onFileChange = function(e) {
|
|
||||||
// TODO accept multiple files
|
|
||||||
var file = e.target.files[0],
|
|
||||||
reader = new FileReader();
|
|
||||||
|
|
||||||
reader.onload = this._bind(this, this.onFileLoad);
|
|
||||||
reader.readAsBinaryString(file);
|
|
||||||
}
|
|
||||||
|
|
||||||
this.onFileLoad = function(e) {
|
|
||||||
var content = e.target.result,
|
|
||||||
string = new BinaryString(content);
|
|
||||||
this.options.onFileLoad(string);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
this._mergeObjects = function(starting, override) {
|
|
||||||
var merged = starting;
|
|
||||||
for (key in override) merged[key] = override[key];
|
|
||||||
|
|
||||||
return merged;
|
|
||||||
}
|
|
||||||
|
|
||||||
this._verifyOptions = function() {
|
|
||||||
if (!(this.options.element && this.options.element.type && this.options.element.type === 'file')) {
|
|
||||||
throw 'Invalid element param in options. Must be a file upload DOM element';
|
|
||||||
}
|
|
||||||
|
|
||||||
if (typeof this.options.onFileLoad !== 'function') {
|
|
||||||
throw 'Invalid onFileLoad param in options. Must be a function';
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
this._verifyDependencies = function() {
|
|
||||||
if (!window.BinaryString) throw 'BinaryString is missing. Check that you\'ve correctly included it';
|
|
||||||
}
|
|
||||||
|
|
||||||
// helper function for binding methods to objects
|
|
||||||
this._bind = function(object, method) {
|
|
||||||
return function() {return method.apply(object, arguments);};
|
|
||||||
}
|
|
||||||
|
|
||||||
this._init(o);
|
|
||||||
}
|
|
|
@ -1,168 +0,0 @@
|
||||||
function BinaryString(source) {
|
|
||||||
this._source = null;
|
|
||||||
this._bytes = [];
|
|
||||||
this._pos = 0;
|
|
||||||
this._length = 0;
|
|
||||||
|
|
||||||
this._init = function(source) {
|
|
||||||
this._source = source;
|
|
||||||
this._bytes = this._stringToBytes(this._source);
|
|
||||||
this._length = this._bytes.length;
|
|
||||||
}
|
|
||||||
|
|
||||||
this.current = function() {return this._pos;}
|
|
||||||
|
|
||||||
this.rewind = function() {return this.jump(0);}
|
|
||||||
this.end = function() {return this.jump(this.length() - 1);}
|
|
||||||
this.next = function() {return this.jump(this.current() + 1);}
|
|
||||||
this.prev = function() {return this.jump(this.current() - 1);}
|
|
||||||
|
|
||||||
this.jump = function(pos) {
|
|
||||||
if (pos < 0 || pos >= this.length()) return false;
|
|
||||||
|
|
||||||
this._pos = pos;
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
this.readByte = function(pos) {
|
|
||||||
pos = (typeof pos == 'number') ? pos : this.current();
|
|
||||||
return this.readBytes(1, pos)[0];
|
|
||||||
}
|
|
||||||
|
|
||||||
this.readBytes = function(length, pos) {
|
|
||||||
length = length || 1;
|
|
||||||
pos = (typeof pos == 'number') ? pos : this.current();
|
|
||||||
|
|
||||||
if (pos > this.length() ||
|
|
||||||
pos < 0 ||
|
|
||||||
length <= 0 ||
|
|
||||||
pos + length > this.length() ||
|
|
||||||
pos + length < 0
|
|
||||||
) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
var bytes = [];
|
|
||||||
|
|
||||||
for (var i = pos; i < pos + length; i++) {
|
|
||||||
bytes.push(this._bytes[i]);
|
|
||||||
}
|
|
||||||
|
|
||||||
return bytes;
|
|
||||||
}
|
|
||||||
|
|
||||||
this.length = function() {return this._length;}
|
|
||||||
|
|
||||||
this.toString = function() {
|
|
||||||
var string = '',
|
|
||||||
length = this.length();
|
|
||||||
|
|
||||||
for (var i = 0; i < length; i++) {
|
|
||||||
string += String.fromCharCode(this.readByte(i));
|
|
||||||
}
|
|
||||||
|
|
||||||
return string;
|
|
||||||
}
|
|
||||||
|
|
||||||
this.toUtf8 = function() {
|
|
||||||
var inc = 0,
|
|
||||||
string = '',
|
|
||||||
length = this.length();
|
|
||||||
|
|
||||||
// determine if first 3 characters are the BOM
|
|
||||||
// then skip them in output if so
|
|
||||||
if (length >= 3 &&
|
|
||||||
this.readByte(0) === 0xEF &&
|
|
||||||
this.readByte(1) === 0xBB &&
|
|
||||||
this.readByte(2) === 0xBF
|
|
||||||
) {
|
|
||||||
inc = 3;
|
|
||||||
}
|
|
||||||
|
|
||||||
for (; inc < length; inc++) {
|
|
||||||
var byte1 = this.readByte(inc),
|
|
||||||
byte2 = 0,
|
|
||||||
byte3 = 0,
|
|
||||||
byte4 = 0,
|
|
||||||
code1 = 0,
|
|
||||||
code2 = 0,
|
|
||||||
point = 0;
|
|
||||||
|
|
||||||
switch (true) {
|
|
||||||
// single byte character; same as ascii
|
|
||||||
case (byte1 < 0x80):
|
|
||||||
code1 = byte1;
|
|
||||||
break;
|
|
||||||
|
|
||||||
// 2 byte character
|
|
||||||
case (byte1 >= 0xC2 && byte1 < 0xE0):
|
|
||||||
byte2 = this.readByte(++inc);
|
|
||||||
|
|
||||||
code1 = ((byte1 & 0x1F) << 6) +
|
|
||||||
(byte2 & 0x3F);
|
|
||||||
break;
|
|
||||||
|
|
||||||
// 3 byte character
|
|
||||||
case (byte1 >= 0xE0 && byte1 < 0xF0):
|
|
||||||
byte2 = this.readByte(++inc);
|
|
||||||
byte3 = this.readByte(++inc);
|
|
||||||
|
|
||||||
code1 = ((byte1 & 0xFF) << 12) +
|
|
||||||
((byte2 & 0x3F) << 6) +
|
|
||||||
(byte3 & 0x3F);
|
|
||||||
break;
|
|
||||||
|
|
||||||
// 4 byte character
|
|
||||||
case (byte1 >= 0xF0 && byte1 < 0xF5):
|
|
||||||
byte2 = this.readByte(++inc);
|
|
||||||
byte3 = this.readByte(++inc);
|
|
||||||
byte4 = this.readByte(++inc);
|
|
||||||
|
|
||||||
point = ((byte1 & 0x07) << 18) +
|
|
||||||
((byte2 & 0x3F) << 12) +
|
|
||||||
((byte3 & 0x3F) << 6) +
|
|
||||||
(byte4 & 0x3F)
|
|
||||||
point -= 0x10000;
|
|
||||||
|
|
||||||
code1 = (point >> 10) + 0xD800;
|
|
||||||
code2 = (point & 0x3FF) + 0xDC00;
|
|
||||||
break;
|
|
||||||
|
|
||||||
default:
|
|
||||||
throw 'Invalid byte ' + this._byteToString(byte1) + ' whilst converting to UTF-8';
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
string += (code2) ? String.fromCharCode(code1, code2)
|
|
||||||
: String.fromCharCode(code1);
|
|
||||||
}
|
|
||||||
|
|
||||||
return string;
|
|
||||||
}
|
|
||||||
|
|
||||||
this.toArray = function() {return this.readBytes(this.length() - 1, 0);}
|
|
||||||
|
|
||||||
|
|
||||||
this._stringToBytes = function(str) {
|
|
||||||
var bytes = [],
|
|
||||||
chr = 0;
|
|
||||||
|
|
||||||
for (var i = 0; i < str.length; i++) {
|
|
||||||
chr = str.charCodeAt(i);
|
|
||||||
bytes.push(chr & 0xFF);
|
|
||||||
}
|
|
||||||
|
|
||||||
return bytes;
|
|
||||||
}
|
|
||||||
|
|
||||||
this._byteToString = function(byte) {
|
|
||||||
var asString = byte.toString(16).toUpperCase();
|
|
||||||
while (asString.length < 2) {
|
|
||||||
asString = '0' + asString;
|
|
||||||
}
|
|
||||||
|
|
||||||
return '0x' + asString;
|
|
||||||
}
|
|
||||||
|
|
||||||
this._init(source);
|
|
||||||
}
|
|
File diff suppressed because it is too large
Load diff
|
@ -1,524 +0,0 @@
|
||||||
/*!
|
|
||||||
jCanvas v2.2.1
|
|
||||||
Caleb Evans
|
|
||||||
2.2.1 revisions by Thinkyhead
|
|
||||||
*/
|
|
||||||
|
|
||||||
(function($, document, Math, Number, undefined) {
|
|
||||||
|
|
||||||
// jC global object
|
|
||||||
var jC = {};
|
|
||||||
jC.originals = {
|
|
||||||
width: 20,
|
|
||||||
height: 20,
|
|
||||||
cornerRadius: 0,
|
|
||||||
fillStyle: 'transparent',
|
|
||||||
strokeStyle: 'transparent',
|
|
||||||
strokeWidth: 5,
|
|
||||||
strokeCap: 'butt',
|
|
||||||
strokeJoin: 'miter',
|
|
||||||
shadowX: 0,
|
|
||||||
shadowY: 0,
|
|
||||||
shadowBlur: 10,
|
|
||||||
shadowColor: 'transparent',
|
|
||||||
x: 0, y: 0,
|
|
||||||
x1: 0, y1: 0,
|
|
||||||
radius: 10,
|
|
||||||
start: 0,
|
|
||||||
end: 360,
|
|
||||||
ccw: false,
|
|
||||||
inDegrees: true,
|
|
||||||
fromCenter: true,
|
|
||||||
closed: false,
|
|
||||||
sides: 3,
|
|
||||||
angle: 0,
|
|
||||||
text: '',
|
|
||||||
font: 'normal 12pt sans-serif',
|
|
||||||
align: 'center',
|
|
||||||
baseline: 'middle',
|
|
||||||
source: '',
|
|
||||||
repeat: 'repeat'
|
|
||||||
};
|
|
||||||
// Duplicate original defaults
|
|
||||||
jC.defaults = $.extend({}, jC.originals);
|
|
||||||
|
|
||||||
// Set global properties
|
|
||||||
function setGlobals(context, map) {
|
|
||||||
context.fillStyle = map.fillStyle;
|
|
||||||
context.strokeStyle = map.strokeStyle;
|
|
||||||
context.lineWidth = map.strokeWidth;
|
|
||||||
context.lineCap = map.strokeCap;
|
|
||||||
context.lineJoin = map.strokeJoin;
|
|
||||||
context.shadowOffsetX = map.shadowX;
|
|
||||||
context.shadowOffsetY = map.shadowY;
|
|
||||||
context.shadowBlur = map.shadowBlur;
|
|
||||||
context.shadowColor = map.shadowColor;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Close path if chosen
|
|
||||||
function closePath(context, map) {
|
|
||||||
if (map.closed === true) {
|
|
||||||
context.closePath();
|
|
||||||
context.fill();
|
|
||||||
context.stroke();
|
|
||||||
} else {
|
|
||||||
context.fill();
|
|
||||||
context.stroke();
|
|
||||||
context.closePath();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Measure angles in degrees if chosen
|
|
||||||
function checkUnits(map) {
|
|
||||||
if (map.inDegrees === true) {
|
|
||||||
return Math.PI / 180;
|
|
||||||
} else {
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Set canvas defaults
|
|
||||||
$.fn.canvas = function(args) {
|
|
||||||
// Reset defaults if no value is passed
|
|
||||||
if (typeof args === 'undefined') {
|
|
||||||
jC.defaults = jC.originals;
|
|
||||||
} else {
|
|
||||||
jC.defaults = $.extend({}, jC.defaults, args);
|
|
||||||
}
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Load canvas
|
|
||||||
$.fn.loadCanvas = function(context) {
|
|
||||||
if (typeof context === 'undefined') {context = '2d';}
|
|
||||||
return this[0].getContext(context);
|
|
||||||
};
|
|
||||||
|
|
||||||
// Create gradient
|
|
||||||
$.fn.gradient = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
// Specify custom defaults
|
|
||||||
gDefaults = {
|
|
||||||
x1: 0, y1: 0,
|
|
||||||
x2: 0, y2: 0,
|
|
||||||
r1: 10, r2: 100
|
|
||||||
},
|
|
||||||
params = $.extend({}, gDefaults, args),
|
|
||||||
gradient, stops = 0, percent, i;
|
|
||||||
|
|
||||||
// Create radial gradient if chosen
|
|
||||||
if (typeof args.r1 === 'undefined' && typeof args.r2 === 'undefined') {
|
|
||||||
gradient = ctx.createLinearGradient(params.x1, params.y1, params.x2, params.y2);
|
|
||||||
} else {
|
|
||||||
gradient = ctx.createRadialGradient(params.x1, params.y1, params.r1, params.x2, params.y2, params.r2);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Count number of color stops
|
|
||||||
for (i=1; i<=Number.MAX_VALUE; i+=1) {
|
|
||||||
if (params['c' + i]) {
|
|
||||||
stops += 1;
|
|
||||||
} else {
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Calculate color stop percentages if absent
|
|
||||||
for (i=1; i<=stops; i+=1) {
|
|
||||||
percent = Math.round((100 / (stops-1)) * (i-1)) / 100;
|
|
||||||
if (typeof params['s' + i] === 'undefined') {
|
|
||||||
params['s' + i] = percent;
|
|
||||||
}
|
|
||||||
gradient.addColorStop(params['s' + i], params['c' + i]);
|
|
||||||
}
|
|
||||||
return gradient;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Create pattern
|
|
||||||
$.fn.pattern = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
params = $.extend({}, jC.defaults, args),
|
|
||||||
pattern,
|
|
||||||
img = document.createElement('img');
|
|
||||||
img.src = params.source;
|
|
||||||
|
|
||||||
// Create pattern
|
|
||||||
function create() {
|
|
||||||
if (img.complete === true) {
|
|
||||||
// Create pattern
|
|
||||||
pattern = ctx.createPattern(img, params.repeat);
|
|
||||||
} else {
|
|
||||||
throw "The pattern has not loaded yet";
|
|
||||||
}
|
|
||||||
}
|
|
||||||
try {
|
|
||||||
create();
|
|
||||||
} catch(error) {
|
|
||||||
img.onload = create;
|
|
||||||
}
|
|
||||||
return pattern;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Clear canvas
|
|
||||||
$.fn.clearCanvas = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
params = $.extend({}, jC.defaults, args);
|
|
||||||
|
|
||||||
// Draw from center if chosen
|
|
||||||
if (params.fromCenter === true) {
|
|
||||||
params.x -= params.width / 2;
|
|
||||||
params.y -= params.height / 2;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Clear entire canvas if chosen
|
|
||||||
ctx.beginPath();
|
|
||||||
if (typeof args === 'undefined') {
|
|
||||||
ctx.clearRect(0, 0, this.width(), this.height());
|
|
||||||
} else {
|
|
||||||
ctx.clearRect(params.x, params.y, params.width, params.height);
|
|
||||||
}
|
|
||||||
ctx.closePath();
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Save canvas
|
|
||||||
$.fn.saveCanvas = function() {
|
|
||||||
var ctx = this.loadCanvas();
|
|
||||||
ctx.save();
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Restore canvas
|
|
||||||
$.fn.restoreCanvas = function() {
|
|
||||||
var ctx = this.loadCanvas();
|
|
||||||
ctx.restore();
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Scale canvas
|
|
||||||
$.fn.scaleCanvas = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
params = $.extend({}, jC.defaults, args);
|
|
||||||
ctx.save();
|
|
||||||
ctx.translate(params.x, params.y);
|
|
||||||
ctx.scale(params.width, params.height);
|
|
||||||
ctx.translate(-params.x, -params.y)
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Translate canvas
|
|
||||||
$.fn.translateCanvas = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
params = $.extend({}, jC.defaults, args);
|
|
||||||
ctx.save();
|
|
||||||
ctx.translate(params.x, params.y);
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Rotate canvas
|
|
||||||
$.fn.rotateCanvas = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
params = $.extend({}, jC.defaults, args),
|
|
||||||
toRad = checkUnits(params);
|
|
||||||
|
|
||||||
ctx.save();
|
|
||||||
ctx.translate(params.x, params.y);
|
|
||||||
ctx.rotate(params.angle * toRad);
|
|
||||||
ctx.translate(-params.x, -params.y);
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Draw rectangle
|
|
||||||
$.fn.drawRect = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
params = $.extend({}, jC.defaults, args),
|
|
||||||
toRad = checkUnits(params),
|
|
||||||
x1, y1, x2, y2, r;
|
|
||||||
setGlobals(ctx, params);
|
|
||||||
|
|
||||||
// Draw from center if chosen
|
|
||||||
if (params.fromCenter === true) {
|
|
||||||
params.x -= params.width / 2;
|
|
||||||
params.y -= params.height / 2;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Draw rounded rectangle if chosen
|
|
||||||
if (params.cornerRadius > 0) {
|
|
||||||
x1 = params.x;
|
|
||||||
y1 = params.y;
|
|
||||||
x2 = params.x + params.width;
|
|
||||||
y2 = params.y + params.height;
|
|
||||||
r = params.cornerRadius;
|
|
||||||
if ((x2 - x1) - (2 * r) < 0) {
|
|
||||||
r = (x2 - x1) / 2;
|
|
||||||
}
|
|
||||||
if ((y2 - y1) - (2 * r) < 0) {
|
|
||||||
r = (y2 - y1) / 2;
|
|
||||||
}
|
|
||||||
ctx.beginPath();
|
|
||||||
ctx.moveTo(x1+r,y1);
|
|
||||||
ctx.lineTo(x2-r,y1);
|
|
||||||
ctx.arc(x2-r, y1+r, r, 270*toRad, 360*toRad, false);
|
|
||||||
ctx.lineTo(x2,y2-r);
|
|
||||||
ctx.arc(x2-r, y2-r, r, 0, 90*toRad, false);
|
|
||||||
ctx.lineTo(x1+r,y2);
|
|
||||||
ctx.arc(x1+r, y2-r, r, 90*toRad, 180*toRad, false);
|
|
||||||
ctx.lineTo(x1,y1+r);
|
|
||||||
ctx.arc(x1+r, y1+r, r, 180*toRad, 270*toRad, false);
|
|
||||||
ctx.fill();
|
|
||||||
ctx.stroke();
|
|
||||||
ctx.closePath();
|
|
||||||
} else {
|
|
||||||
ctx.fillRect(params.x, params.y, params.width, params.height);
|
|
||||||
ctx.strokeRect(params.x, params.y, params.width, params.height);
|
|
||||||
}
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Draw arc
|
|
||||||
$.fn.drawArc = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
params = $.extend({}, jC.defaults, args),
|
|
||||||
toRad = checkUnits(params);
|
|
||||||
setGlobals(ctx, params);
|
|
||||||
|
|
||||||
// Draw from center if chosen
|
|
||||||
if (params.fromCenter === false) {
|
|
||||||
params.x += params.radius;
|
|
||||||
params.y += params.radius;
|
|
||||||
}
|
|
||||||
|
|
||||||
ctx.beginPath();
|
|
||||||
ctx.arc(params.x, params.y, params.radius, (params.start*toRad)-(Math.PI/2), (params.end*toRad)-(Math.PI/2), params.ccw);
|
|
||||||
// Close path if chosen
|
|
||||||
closePath(ctx, params);
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Draw ellipse
|
|
||||||
$.fn.drawEllipse = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
params = $.extend({}, jC.defaults, args),
|
|
||||||
controlW = params.width * (4/3);
|
|
||||||
setGlobals(ctx, params);
|
|
||||||
|
|
||||||
// Draw from center if chosen
|
|
||||||
if (params.fromCenter === false) {
|
|
||||||
params.x += params.width / 2;
|
|
||||||
params.y += params.height / 2;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Increment coordinates to prevent negative values
|
|
||||||
params.x += 1e-10;
|
|
||||||
params.y += 1e-10;
|
|
||||||
|
|
||||||
// Create ellipse
|
|
||||||
ctx.beginPath();
|
|
||||||
ctx.moveTo(params.x, params.y-params.height/2);
|
|
||||||
ctx.bezierCurveTo(params.x-controlW/2,params.y-params.height/2,
|
|
||||||
params.x-controlW/2,params.y+params.height/2,
|
|
||||||
params.x,params.y+params.height/2);
|
|
||||||
ctx.bezierCurveTo(params.x+controlW/2,params.y+params.height/2,
|
|
||||||
params.x+controlW/2,params.y-params.height/2,
|
|
||||||
params.x,params.y-params.height/2);
|
|
||||||
ctx.closePath();
|
|
||||||
ctx.fill();
|
|
||||||
ctx.stroke();
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Draw line
|
|
||||||
$.fn.drawLine = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
params = $.extend({}, jC.defaults, args),
|
|
||||||
max = Number.MAX_VALUE, l,
|
|
||||||
lx, ly;
|
|
||||||
setGlobals(ctx, params);
|
|
||||||
|
|
||||||
// Draw each point
|
|
||||||
ctx.beginPath();
|
|
||||||
ctx.moveTo(params.x1, params.y1);
|
|
||||||
for (l=2; l<max; l+=1) {
|
|
||||||
lx = params['x' + l];
|
|
||||||
ly = params['y' + l];
|
|
||||||
// Stop loop when all points are drawn
|
|
||||||
if (typeof lx === 'undefined' || typeof ly === 'undefined') {
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
ctx.lineTo(lx, ly);
|
|
||||||
}
|
|
||||||
// Close path if chosen
|
|
||||||
closePath(ctx, params);
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Draw quadratic curve
|
|
||||||
$.fn.drawQuad = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
params = $.extend({}, jC.defaults, args),
|
|
||||||
max = Number.MAX_VALUE, l,
|
|
||||||
lx, ly, lcx, lcy;
|
|
||||||
setGlobals(ctx, params);
|
|
||||||
|
|
||||||
// Draw each point
|
|
||||||
ctx.beginPath();
|
|
||||||
ctx.moveTo(params.x1, params.y1);
|
|
||||||
for (l=2; l<max; l+=1) {
|
|
||||||
lx = params['x' + l];
|
|
||||||
if (typeof lx === 'undefined') break;
|
|
||||||
ly = params['y' + l];
|
|
||||||
if (typeof ly === 'undefined') break;
|
|
||||||
lcx = params['cx' + (l-1)];
|
|
||||||
if (typeof lcx === 'undefined') break;
|
|
||||||
lcy = params['cy' + (l-1)];
|
|
||||||
if (typeof lcy === 'undefined') break;
|
|
||||||
ctx.quadraticCurveTo(lcx, lcy, lx, ly);
|
|
||||||
}
|
|
||||||
// Close path if chosen
|
|
||||||
closePath(ctx, params);
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Draw Bezier curve
|
|
||||||
$.fn.drawBezier = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
params = $.extend({}, jC.defaults, args),
|
|
||||||
max = Number.MAX_VALUE,
|
|
||||||
l=2, lc=1, lx, ly, lcx1, lcy1, lcx2, lcy2, i;
|
|
||||||
setGlobals(ctx, params);
|
|
||||||
|
|
||||||
// Draw each point
|
|
||||||
ctx.beginPath();
|
|
||||||
ctx.moveTo(params.x1, params.y1);
|
|
||||||
for (i=2; i<max; i+=1) {
|
|
||||||
lx = params['x' + l];
|
|
||||||
if (typeof lx === 'undefined') break;
|
|
||||||
ly = params['y' + l];
|
|
||||||
if (typeof ly === 'undefined') break;
|
|
||||||
lcx1 = params['cx' + lc];
|
|
||||||
if (typeof lcx1 === 'undefined') break;
|
|
||||||
lcy1 = params['cy' + lc];
|
|
||||||
if (typeof lcy1 === 'undefined') break;
|
|
||||||
lcx2 = params['cx' + (lc+1)];
|
|
||||||
if (typeof lcx2 === 'undefined') break;
|
|
||||||
lcy2 = params['cy' + (lc+1)];
|
|
||||||
if (typeof lcy2 === 'undefined') break;
|
|
||||||
ctx.bezierCurveTo(lcx1, lcy1, lcx2, lcy2, lx, ly);
|
|
||||||
l += 1;
|
|
||||||
lc += 2;
|
|
||||||
}
|
|
||||||
// Close path if chosen
|
|
||||||
closePath(ctx, params);
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Draw text
|
|
||||||
$.fn.drawText = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
params = $.extend({}, jC.defaults, args);
|
|
||||||
setGlobals(ctx, params);
|
|
||||||
|
|
||||||
// Set text-specific properties
|
|
||||||
ctx.textBaseline = params.baseline;
|
|
||||||
ctx.textAlign = params.align;
|
|
||||||
ctx.font = params.font;
|
|
||||||
|
|
||||||
ctx.strokeText(params.text, params.x, params.y);
|
|
||||||
ctx.fillText(params.text, params.x, params.y);
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Draw image
|
|
||||||
$.fn.drawImage = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
params = $.extend({}, jC.defaults, args),
|
|
||||||
// Define image source
|
|
||||||
img = document.createElement('img');
|
|
||||||
img.src = params.source;
|
|
||||||
setGlobals(ctx, params);
|
|
||||||
|
|
||||||
// Draw image function
|
|
||||||
function draw() {
|
|
||||||
if (img.complete) {
|
|
||||||
|
|
||||||
var scaleFac = img.width / img.height;
|
|
||||||
|
|
||||||
// If width/height are specified
|
|
||||||
if (typeof args.width !== 'undefined' && typeof args.height !== 'undefined') {
|
|
||||||
img.width = args.width;
|
|
||||||
img.height = args.height;
|
|
||||||
// If width is specified
|
|
||||||
} else if (typeof args.width !== 'undefined' && typeof args.height === 'undefined') {
|
|
||||||
img.width = args.width;
|
|
||||||
img.height = img.width / scaleFac;
|
|
||||||
// If height is specified
|
|
||||||
} else if (typeof args.width === 'undefined' && typeof args.height !== 'undefined') {
|
|
||||||
img.height = args.height;
|
|
||||||
img.width = img.height * scaleFac;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Draw from center if chosen
|
|
||||||
if (params.fromCenter === true) {
|
|
||||||
params.x -= img.width / 2;
|
|
||||||
params.y -= img.height / 2;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Draw image
|
|
||||||
ctx.drawImage(img, params.x, params.y, img.width, img.height);
|
|
||||||
} else {
|
|
||||||
throw "The image has not loaded yet.";
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
function dodraw() {
|
|
||||||
// console.log("dodraw...");
|
|
||||||
try {
|
|
||||||
// console.log("dodraw...try...");
|
|
||||||
draw();
|
|
||||||
}
|
|
||||||
catch(error) {
|
|
||||||
// console.log("dodraw...catch: " + error);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Draw image if already loaded
|
|
||||||
// console.log("--------------------");
|
|
||||||
// console.log("drawImage " + img.src);
|
|
||||||
try {
|
|
||||||
// console.log("try...");
|
|
||||||
draw();
|
|
||||||
} catch(error) {
|
|
||||||
// console.log("catch: " + error);
|
|
||||||
img.onload = dodraw;
|
|
||||||
}
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
// Draw polygon
|
|
||||||
$.fn.drawPolygon = function(args) {
|
|
||||||
var ctx = this.loadCanvas(),
|
|
||||||
params = $.extend({}, jC.defaults, args),
|
|
||||||
theta, dtheta, x, y,
|
|
||||||
toRad = checkUnits(params), i;
|
|
||||||
setGlobals(ctx, params);
|
|
||||||
|
|
||||||
if (params.sides >= 3) {
|
|
||||||
// Calculate points and draw
|
|
||||||
theta = (Math.PI/2) + (Math.PI/params.sides) + (params.angle*toRad);
|
|
||||||
dtheta = (Math.PI*2) / params.sides;
|
|
||||||
for (i=0; i<params.sides; i+=1) {
|
|
||||||
x = params.x + (params.radius * Math.cos(theta)) + 1e-10;
|
|
||||||
y = params.y + (params.radius * Math.sin(theta)) + 1e-10;
|
|
||||||
if (params.fromCenter === false) {
|
|
||||||
x += params.radius;
|
|
||||||
y += params.radius;
|
|
||||||
}
|
|
||||||
ctx.lineTo(x, y);
|
|
||||||
theta += dtheta;
|
|
||||||
}
|
|
||||||
closePath(ctx, params);
|
|
||||||
}
|
|
||||||
return this;
|
|
||||||
};
|
|
||||||
|
|
||||||
return window.jCanvas = jC;
|
|
||||||
}(jQuery, document, Math, Number));
|
|
4
Marlin/configurator/js/jquery-2.1.3.min.js
vendored
4
Marlin/configurator/js/jquery-2.1.3.min.js
vendored
File diff suppressed because one or more lines are too long
|
@ -1,220 +0,0 @@
|
||||||
/*!
|
|
||||||
* jQuery "stepper" Plugin
|
|
||||||
* version 0.0.1
|
|
||||||
* @requires jQuery v1.3.2 or later
|
|
||||||
* @requires jCanvas
|
|
||||||
*
|
|
||||||
* Authored 2011-06-11 Scott Lahteine (thinkyhead.com)
|
|
||||||
*
|
|
||||||
* A very simple numerical stepper.
|
|
||||||
* TODO: place arrows based on div size, make 50/50 width
|
|
||||||
*
|
|
||||||
* Usage example:
|
|
||||||
*
|
|
||||||
* $('#mydiv').jstepper({
|
|
||||||
* min: 1,
|
|
||||||
* max: 4,
|
|
||||||
* val: 1,
|
|
||||||
* arrowWidth: 15,
|
|
||||||
* arrowHeight: '22px',
|
|
||||||
* color: '#FFF',
|
|
||||||
* acolor: '#F70',
|
|
||||||
* hcolor: '#FF0',
|
|
||||||
* id: 'select-me',
|
|
||||||
* stepperClass: 'inner',
|
|
||||||
* textStyle: {width:'1.5em',fontSize:'20px',textAlign:'center'},
|
|
||||||
* onChange: function(v) { },
|
|
||||||
* });
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
;(function($) {
|
|
||||||
var un = 'undefined';
|
|
||||||
|
|
||||||
$.jstepperArrows = [
|
|
||||||
{ name:'prev', poly:[[1.0,0],[0,0.5],[1.0,1.0]] },
|
|
||||||
{ name:'next', poly:[[0,0],[1.0,0.5],[0,1.0]] }
|
|
||||||
];
|
|
||||||
|
|
||||||
$.fn.jstepper = function(args) {
|
|
||||||
|
|
||||||
return this.each(function() {
|
|
||||||
|
|
||||||
var defaults = {
|
|
||||||
min: 1,
|
|
||||||
max: null,
|
|
||||||
val: null,
|
|
||||||
active: true,
|
|
||||||
placeholder: null,
|
|
||||||
arrowWidth: 0,
|
|
||||||
arrowHeight: 0,
|
|
||||||
color: '#FFF',
|
|
||||||
hcolor: '#FF0',
|
|
||||||
acolor: '#F80',
|
|
||||||
id: '',
|
|
||||||
stepperClass: '',
|
|
||||||
textStyle: '',
|
|
||||||
onChange: (function(v){ if (typeof console.log !== 'undefined') console.log("val="+v); })
|
|
||||||
};
|
|
||||||
|
|
||||||
args = $.extend(defaults, args || {});
|
|
||||||
|
|
||||||
var min = args.min * 1,
|
|
||||||
max = (args.max !== null) ? args.max * 1 : min,
|
|
||||||
span = max - min + 1,
|
|
||||||
val = (args.val !== null) ? args.val * 1 : min,
|
|
||||||
active = !args.disabled,
|
|
||||||
placeholder = args.placeholder,
|
|
||||||
arrowWidth = 1 * args.arrowWidth.toString().replace(/px/,''),
|
|
||||||
arrowHeight = 1 * args.arrowHeight.toString().replace(/px/,''),
|
|
||||||
color = args.color,
|
|
||||||
hcolor = args.hcolor,
|
|
||||||
acolor = args.acolor,
|
|
||||||
$prev = $('<a href="#prev" style="cursor:w-resize;"><canvas/></a>'),
|
|
||||||
$marq = $('<div class="number"/>').css({float:'left',textAlign:'center'}),
|
|
||||||
$next = $('<a href="#next" style="cursor:e-resize;"><canvas/></a>'),
|
|
||||||
arrow = [ $prev.find('canvas')[0], $next.find('canvas')[0] ],
|
|
||||||
$stepper = $('<span class="jstepper"/>').append($prev).append($marq).append($next).append('<div style="clear:both;"/>'),
|
|
||||||
onChange = args.onChange;
|
|
||||||
|
|
||||||
if (args.id) $stepper[0].id = args.id;
|
|
||||||
if (args.stepperClass) $stepper.addClass(args.stepperClass);
|
|
||||||
if (args.textStyle) $marq.css(args.textStyle);
|
|
||||||
|
|
||||||
// replace a span, but embed elsewhere
|
|
||||||
if (this.tagName == 'SPAN') {
|
|
||||||
var previd = this.id;
|
|
||||||
$(this).replaceWith($stepper);
|
|
||||||
if (previd) $stepper.attr('id',previd);
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
$(this).append($stepper);
|
|
||||||
}
|
|
||||||
|
|
||||||
// hook to call functions on this object
|
|
||||||
$stepper[0].ui = {
|
|
||||||
|
|
||||||
refresh: function() {
|
|
||||||
this.updateNumber();
|
|
||||||
this._drawArrow(0, 1);
|
|
||||||
this._drawArrow(1, 1);
|
|
||||||
return this;
|
|
||||||
},
|
|
||||||
|
|
||||||
_drawArrow: function(i,state) {
|
|
||||||
var $elm = $(arrow[i]),
|
|
||||||
desc = $.jstepperArrows[i],
|
|
||||||
fillStyle = (state == 2) ? hcolor : (state == 3) ? acolor : color,
|
|
||||||
draw = { fillStyle: fillStyle },
|
|
||||||
w = $elm.width(), h = $elm.height();
|
|
||||||
|
|
||||||
if (w <= 0) w = $elm.attr('width');
|
|
||||||
if (h <= 0) h = $elm.attr('height');
|
|
||||||
|
|
||||||
$.each(desc.poly,function(i,v){
|
|
||||||
++i;
|
|
||||||
draw['x'+i] = v[0] * w;
|
|
||||||
draw['y'+i] = v[1] * h;
|
|
||||||
});
|
|
||||||
$elm.restoreCanvas().clearCanvas().drawLine(draw);
|
|
||||||
},
|
|
||||||
|
|
||||||
updateNumber: function() {
|
|
||||||
$marq.html((active || placeholder === null) ? val.toString() : placeholder);
|
|
||||||
return this;
|
|
||||||
},
|
|
||||||
|
|
||||||
_doclick: function(i) {
|
|
||||||
this.add(i ? 1 : -1);
|
|
||||||
this._drawArrow(i, 3);
|
|
||||||
var self = this;
|
|
||||||
setTimeout(function(){ self._drawArrow(i, 2); }, 50);
|
|
||||||
},
|
|
||||||
|
|
||||||
add: function(x) {
|
|
||||||
val = (((val - min) + x + span) % span) + min;
|
|
||||||
this.updateNumber();
|
|
||||||
this.didChange(val);
|
|
||||||
return this;
|
|
||||||
},
|
|
||||||
|
|
||||||
min: function(v) {
|
|
||||||
if (typeof v === un) return min;
|
|
||||||
this.setRange(v,max);
|
|
||||||
return this;
|
|
||||||
},
|
|
||||||
|
|
||||||
max: function(v) {
|
|
||||||
if (typeof v === un) return max;
|
|
||||||
this.setRange(min,v);
|
|
||||||
return this;
|
|
||||||
},
|
|
||||||
|
|
||||||
val: function(v) {
|
|
||||||
if (typeof v === un) return val;
|
|
||||||
val = (((v - min) + span) % span) + min;
|
|
||||||
this.updateNumber();
|
|
||||||
return this;
|
|
||||||
},
|
|
||||||
|
|
||||||
setRange: function(lo, hi, ini) {
|
|
||||||
if (lo > hi) hi = (lo += hi -= lo) - hi;
|
|
||||||
min = lo; max = hi; span = hi - lo + 1;
|
|
||||||
if (typeof ini !== un) val = ini;
|
|
||||||
if (val < min) val = min;
|
|
||||||
if (val > max) val = max;
|
|
||||||
this.updateNumber();
|
|
||||||
return this;
|
|
||||||
},
|
|
||||||
|
|
||||||
active: function(a) {
|
|
||||||
if (typeof a === un) return active;
|
|
||||||
(active = a) ? $marq.removeClass('inactive') : $marq.addClass('inactive');
|
|
||||||
this.updateNumber();
|
|
||||||
return this;
|
|
||||||
},
|
|
||||||
|
|
||||||
disable: function() { this.active(false); return this; },
|
|
||||||
enable: function() { this.active(true); return this; },
|
|
||||||
|
|
||||||
clearPlaceholder: function() {
|
|
||||||
this.setPlaceholder(null);
|
|
||||||
return this;
|
|
||||||
},
|
|
||||||
setPlaceholder: function(p) {
|
|
||||||
placeholder = p;
|
|
||||||
if (!active) this.updateNumber();
|
|
||||||
return this;
|
|
||||||
},
|
|
||||||
|
|
||||||
didChange: onChange
|
|
||||||
|
|
||||||
};
|
|
||||||
|
|
||||||
// set hover and click for each arrow
|
|
||||||
$.each($.jstepperArrows, function(i,desc) {
|
|
||||||
var $elm = $(arrow[i]),
|
|
||||||
w = arrowWidth ? arrowWidth : $elm.width() ? $elm.width() : 15,
|
|
||||||
h = arrowHeight ? arrowHeight : $elm.height() ? $elm.height() : 24;
|
|
||||||
$elm[0]._index = i;
|
|
||||||
$elm
|
|
||||||
.css({float:'left'})
|
|
||||||
.attr({width:w,height:h,'class':desc.name})
|
|
||||||
.hover(
|
|
||||||
function(e) { $stepper[0].ui._drawArrow(e.target._index, 2); },
|
|
||||||
function(e) { $stepper[0].ui._drawArrow(e.target._index, 1); }
|
|
||||||
)
|
|
||||||
.click(function(e){
|
|
||||||
$stepper[0].ui._doclick(e.target._index);
|
|
||||||
return false;
|
|
||||||
});
|
|
||||||
});
|
|
||||||
|
|
||||||
// init the visuals first time
|
|
||||||
$stepper[0].ui.refresh();
|
|
||||||
|
|
||||||
}); // this.each
|
|
||||||
|
|
||||||
}; // $.fn.jstepper
|
|
||||||
|
|
||||||
})( jQuery );
|
|
||||||
|
|
14
Marlin/configurator/js/jszip.min.js
vendored
14
Marlin/configurator/js/jszip.min.js
vendored
File diff suppressed because one or more lines are too long
138
Marlin/dac_mcp4728.cpp
Normal file
138
Marlin/dac_mcp4728.cpp
Normal file
|
@ -0,0 +1,138 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* mcp4728.cpp - Arduino library for MicroChip MCP4728 I2C D/A converter
|
||||||
|
*
|
||||||
|
* For implementation details, please take a look at the datasheet:
|
||||||
|
* http://ww1.microchip.com/downloads/en/DeviceDoc/22187a.pdf
|
||||||
|
*
|
||||||
|
* For discussion and feedback, please go to:
|
||||||
|
* http://arduino.cc/forum/index.php/topic,51842.0.html
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "dac_mcp4728.h"
|
||||||
|
|
||||||
|
#if ENABLED(DAC_STEPPER_CURRENT)
|
||||||
|
|
||||||
|
uint16_t mcp4728_values[4];
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Begin I2C, get current values (input register and eeprom) of mcp4728
|
||||||
|
*/
|
||||||
|
void mcp4728_init() {
|
||||||
|
Wire.begin();
|
||||||
|
Wire.requestFrom(int(DAC_DEV_ADDRESS), 24);
|
||||||
|
while(Wire.available()) {
|
||||||
|
int deviceID = Wire.receive();
|
||||||
|
int hiByte = Wire.receive();
|
||||||
|
int loByte = Wire.receive();
|
||||||
|
|
||||||
|
int isEEPROM = (deviceID & 0B00001000) >> 3;
|
||||||
|
int channel = (deviceID & 0B00110000) >> 4;
|
||||||
|
if (isEEPROM != 1) {
|
||||||
|
mcp4728_values[channel] = word((hiByte & 0B00001111), loByte);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Write input resister value to specified channel using fastwrite method.
|
||||||
|
* Channel : 0-3, Values : 0-4095
|
||||||
|
*/
|
||||||
|
uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value) {
|
||||||
|
mcp4728_values[channel] = value;
|
||||||
|
return mcp4728_fastWrite();
|
||||||
|
}
|
||||||
|
/**
|
||||||
|
* Write all input resistor values to EEPROM using SequencialWrite method.
|
||||||
|
* This will update both input register and EEPROM value
|
||||||
|
* This will also write current Vref, PowerDown, Gain settings to EEPROM
|
||||||
|
*/
|
||||||
|
uint8_t mcp4728_eepromWrite() {
|
||||||
|
Wire.beginTransmission(DAC_DEV_ADDRESS);
|
||||||
|
Wire.send(SEQWRITE);
|
||||||
|
for (uint8_t channel=0; channel <= 3; channel++) {
|
||||||
|
Wire.send(DAC_STEPPER_VREF << 7 | 0 << 5 | DAC_STEPPER_GAIN << 4 | highByte(mcp4728_values[channel]));
|
||||||
|
Wire.send(lowByte(mcp4728_values[channel]));
|
||||||
|
}
|
||||||
|
return Wire.endTransmission();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Write Voltage reference setting to all input regiters
|
||||||
|
*/
|
||||||
|
uint8_t mcp4728_setVref_all(uint8_t value) {
|
||||||
|
Wire.beginTransmission(DAC_DEV_ADDRESS);
|
||||||
|
Wire.send(VREFWRITE | value << 3 | value << 2 | value << 1 | value);
|
||||||
|
return Wire.endTransmission();
|
||||||
|
}
|
||||||
|
/**
|
||||||
|
* Write Gain setting to all input regiters
|
||||||
|
*/
|
||||||
|
uint8_t mcp4728_setGain_all(uint8_t value) {
|
||||||
|
Wire.beginTransmission(DAC_DEV_ADDRESS);
|
||||||
|
Wire.send(GAINWRITE | value << 3 | value << 2 | value << 1 | value);
|
||||||
|
return Wire.endTransmission();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Return Input Regiter value
|
||||||
|
*/
|
||||||
|
uint16_t mcp4728_getValue(uint8_t channel) { return mcp4728_values[channel]; }
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Steph: Might be useful in the future
|
||||||
|
* Return Vout
|
||||||
|
*
|
||||||
|
uint16_t mcp4728_getVout(uint8_t channel) {
|
||||||
|
uint32_t vref = 2048;
|
||||||
|
uint32_t vOut = (vref * mcp4728_values[channel] * (_DAC_STEPPER_GAIN + 1)) / 4096;
|
||||||
|
if (vOut > defaultVDD) vOut = defaultVDD;
|
||||||
|
return vOut;
|
||||||
|
}
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* FastWrite input register values - All DAC ouput update. refer to DATASHEET 5.6.1
|
||||||
|
* DAC Input and PowerDown bits update.
|
||||||
|
* No EEPROM update
|
||||||
|
*/
|
||||||
|
uint8_t mcp4728_fastWrite() {
|
||||||
|
Wire.beginTransmission(DAC_DEV_ADDRESS);
|
||||||
|
for (uint8_t channel=0; channel <= 3; channel++) {
|
||||||
|
Wire.send(highByte(mcp4728_values[channel]));
|
||||||
|
Wire.send(lowByte(mcp4728_values[channel]));
|
||||||
|
}
|
||||||
|
return Wire.endTransmission();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Common function for simple general commands
|
||||||
|
*/
|
||||||
|
uint8_t mcp4728_simpleCommand(byte simpleCommand) {
|
||||||
|
Wire.beginTransmission(GENERALCALL);
|
||||||
|
Wire.send(simpleCommand);
|
||||||
|
return Wire.endTransmission();
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // DAC_STEPPER_CURRENT
|
66
Marlin/dac_mcp4728.h
Normal file
66
Marlin/dac_mcp4728.h
Normal file
|
@ -0,0 +1,66 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Arduino library for MicroChip MCP4728 I2C D/A converter.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef mcp4728_h
|
||||||
|
#define mcp4728_h
|
||||||
|
|
||||||
|
#include "Configuration.h"
|
||||||
|
#include "Configuration_adv.h"
|
||||||
|
|
||||||
|
#if ENABLED(DAC_STEPPER_CURRENT)
|
||||||
|
#include "WProgram.h"
|
||||||
|
#include "Wire.h"
|
||||||
|
//#include <Wire.h>
|
||||||
|
|
||||||
|
#define defaultVDD 5000
|
||||||
|
#define BASE_ADDR 0x60
|
||||||
|
#define RESET 0B00000110
|
||||||
|
#define WAKE 0B00001001
|
||||||
|
#define UPDATE 0B00001000
|
||||||
|
#define MULTIWRITE 0B01000000
|
||||||
|
#define SINGLEWRITE 0B01011000
|
||||||
|
#define SEQWRITE 0B01010000
|
||||||
|
#define VREFWRITE 0B10000000
|
||||||
|
#define GAINWRITE 0B11000000
|
||||||
|
#define POWERDOWNWRITE 0B10100000
|
||||||
|
#define GENERALCALL 0B0000000
|
||||||
|
#define GAINWRITE 0B11000000
|
||||||
|
|
||||||
|
// This is taken from the original lib, makes it easy to edit if needed
|
||||||
|
#define DAC_DEV_ADDRESS (BASE_ADDR | 0x00)
|
||||||
|
|
||||||
|
void mcp4728_init();
|
||||||
|
uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value);
|
||||||
|
uint8_t mcp4728_eepromWrite();
|
||||||
|
uint8_t mcp4728_setVref_all(uint8_t value);
|
||||||
|
uint8_t mcp4728_setGain_all(uint8_t value);
|
||||||
|
uint16_t mcp4728_getValue(uint8_t channel);
|
||||||
|
uint8_t mcp4728_fastWrite();
|
||||||
|
uint8_t mcp4728_simpleCommand(byte simpleCommand);
|
||||||
|
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
|
@ -1,3 +1,25 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
#include "Configuration.h"
|
#include "Configuration.h"
|
||||||
|
|
||||||
#if ENABLED(DIGIPOT_I2C)
|
#if ENABLED(DIGIPOT_I2C)
|
||||||
|
|
|
@ -1,6 +1,31 @@
|
||||||
// BitMap for splashscreen
|
/**
|
||||||
// Generated with: http://www.digole.com/tools/PicturetoC_Hex_converter.php
|
* Marlin 3D Printer Firmware
|
||||||
// Please note that using the high-res version takes 402Bytes of PROGMEM.
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* BitMap for splashscreen
|
||||||
|
* Generated with: http://www.digole.com/tools/PicturetoC_Hex_converter.php
|
||||||
|
* Please note that using the high-res version takes 402Bytes of PROGMEM.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define START_BMPHIGH
|
//#define START_BMPHIGH
|
||||||
|
|
||||||
#if ENABLED(SHOW_BOOTSCREEN)
|
#if ENABLED(SHOW_BOOTSCREEN)
|
||||||
|
|
|
@ -1,4 +1,26 @@
|
||||||
/*
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
Fontname: -Misc-Fixed-Medium-R-Normal--9-90-75-75-C-60-ISO10646-1
|
Fontname: -Misc-Fixed-Medium-R-Normal--9-90-75-75-C-60-ISO10646-1
|
||||||
Copyright: Public domain font. Share and enjoy.
|
Copyright: Public domain font. Share and enjoy.
|
||||||
Capital A Height: 6, '1' Height: 6
|
Capital A Height: 6, '1' Height: 6
|
||||||
|
|
|
@ -1,4 +1,26 @@
|
||||||
/*
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
Fontname: HD44780_C v1.2
|
Fontname: HD44780_C v1.2
|
||||||
Copyright: A. Hardtung, public domain
|
Copyright: A. Hardtung, public domain
|
||||||
Capital A Height: 7, '1' Height: 7
|
Capital A Height: 7, '1' Height: 7
|
||||||
|
|
|
@ -1,8 +1,30 @@
|
||||||
/*
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
Fontname: HD44780_J
|
Fontname: HD44780_J
|
||||||
Copyright: A. Hardtung, public domain
|
Copyright: A. Hardtung, public domain
|
||||||
Capital A Height: 7, '1' Height: 7
|
Capital A Height: 7, '1' Height: 7
|
||||||
Calculated Max Values w= 6 h=10 x= 2 y= 8 dx= 6 dy= 0 ascent= 8 len= 8
|
Calculated Max Values w= 6 h=10 x= 2 y= 5 dx= 6 dy= 0 ascent= 8 len= 8
|
||||||
Font Bounding box w= 6 h= 9 x= 0 y=-2
|
Font Bounding box w= 6 h= 9 x= 0 y=-2
|
||||||
Calculated Min Values x= 0 y=-2 dx= 0 dy= 0
|
Calculated Min Values x= 0 y=-2 dx= 0 dy= 0
|
||||||
Pure Font ascent = 7 descent=-1
|
Pure Font ascent = 7 descent=-1
|
||||||
|
@ -10,9 +32,9 @@
|
||||||
Max Font ascent = 8 descent=-2
|
Max Font ascent = 8 descent=-2
|
||||||
*/
|
*/
|
||||||
#include <U8glib.h>
|
#include <U8glib.h>
|
||||||
const u8g_fntpgm_uint8_t HD44780_J_5x7[2491] U8G_SECTION(".progmem.HD44780_J_5x7") = {
|
const u8g_fntpgm_uint8_t HD44780_J_5x7[2492] U8G_SECTION(".progmem.HD44780_J_5x7") = {
|
||||||
0, 6, 9, 0, 254, 7, 1, 145, 3, 34, 32, 255, 255, 8, 254, 7,
|
0, 6, 9, 0, 254, 7, 1, 145, 3, 34, 32, 255, 255, 8, 254, 7,
|
||||||
255, 0, 0, 0, 6, 0, 8, 1, 7, 7, 6, 2, 0, 128, 128, 128,
|
255, 0, 0, 0, 6, 0, 0, 1, 7, 7, 6, 2, 0, 128, 128, 128,
|
||||||
128, 128, 0, 128, 3, 2, 2, 6, 1, 5, 160, 160, 5, 7, 7, 6,
|
128, 128, 0, 128, 3, 2, 2, 6, 1, 5, 160, 160, 5, 7, 7, 6,
|
||||||
0, 0, 80, 80, 248, 80, 248, 80, 80, 5, 7, 7, 6, 0, 0, 32,
|
0, 0, 80, 80, 248, 80, 248, 80, 80, 5, 7, 7, 6, 0, 0, 32,
|
||||||
120, 160, 112, 40, 240, 32, 5, 7, 7, 6, 0, 0, 192, 200, 16, 32,
|
120, 160, 112, 40, 240, 32, 5, 7, 7, 6, 0, 0, 192, 200, 16, 32,
|
||||||
|
@ -84,19 +106,19 @@ const u8g_fntpgm_uint8_t HD44780_J_5x7[2491] U8G_SECTION(".progmem.HD44780_J_5x7
|
||||||
128, 64, 64, 32, 1, 7, 7, 6, 2, 0, 128, 128, 128, 128, 128, 128,
|
128, 64, 64, 32, 1, 7, 7, 6, 2, 0, 128, 128, 128, 128, 128, 128,
|
||||||
128, 3, 7, 7, 6, 1, 0, 128, 64, 64, 32, 64, 64, 128, 5, 5,
|
128, 3, 7, 7, 6, 1, 0, 128, 64, 64, 32, 64, 64, 128, 5, 5,
|
||||||
5, 6, 0, 1, 32, 16, 248, 16, 32, 5, 5, 5, 6, 0, 1, 32,
|
5, 6, 0, 1, 32, 16, 248, 16, 32, 5, 5, 5, 6, 0, 1, 32,
|
||||||
64, 248, 64, 32, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8,
|
64, 248, 64, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0,
|
||||||
0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6,
|
0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6,
|
||||||
0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0,
|
0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0,
|
||||||
0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8,
|
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0,
|
||||||
0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6,
|
0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6,
|
||||||
0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0,
|
0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0,
|
||||||
0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8,
|
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0,
|
||||||
0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6,
|
0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6,
|
||||||
0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0,
|
0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0,
|
||||||
0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8,
|
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0,
|
||||||
0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6,
|
0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6,
|
||||||
0, 8, 0, 0, 0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 0, 0,
|
0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0,
|
||||||
0, 6, 0, 8, 0, 0, 0, 6, 0, 8, 3, 3, 3, 6, 0, 0,
|
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 3, 3, 3, 6, 0, 0,
|
||||||
224, 160, 224, 3, 4, 4, 6, 2, 3, 224, 128, 128, 128, 3, 4, 4,
|
224, 160, 224, 3, 4, 4, 6, 2, 3, 224, 128, 128, 128, 3, 4, 4,
|
||||||
6, 0, 0, 32, 32, 32, 224, 3, 3, 3, 6, 0, 0, 128, 64, 32,
|
6, 0, 0, 32, 32, 32, 224, 3, 3, 3, 6, 0, 0, 128, 64, 32,
|
||||||
2, 2, 2, 6, 1, 2, 192, 192, 5, 6, 6, 6, 0, 0, 248, 8,
|
2, 2, 2, 6, 1, 2, 192, 192, 5, 6, 6, 6, 0, 0, 248, 8,
|
||||||
|
@ -106,7 +128,7 @@ const u8g_fntpgm_uint8_t HD44780_J_5x7[2491] U8G_SECTION(".progmem.HD44780_J_5x7
|
||||||
5, 5, 6, 0, 0, 16, 248, 48, 80, 144, 5, 5, 5, 6, 0, 0,
|
5, 5, 6, 0, 0, 16, 248, 48, 80, 144, 5, 5, 5, 6, 0, 0,
|
||||||
64, 248, 72, 80, 64, 5, 4, 4, 6, 0, 0, 112, 16, 16, 248, 4,
|
64, 248, 72, 80, 64, 5, 4, 4, 6, 0, 0, 112, 16, 16, 248, 4,
|
||||||
5, 5, 6, 0, 0, 240, 16, 240, 16, 240, 5, 4, 4, 6, 0, 0,
|
5, 5, 6, 0, 0, 240, 16, 240, 16, 240, 5, 4, 4, 6, 0, 0,
|
||||||
168, 168, 8, 48, 5, 1, 1, 6, 0, 4, 248, 5, 7, 7, 6, 0,
|
168, 168, 8, 48, 5, 1, 1, 6, 0, 3, 248, 5, 7, 7, 6, 0,
|
||||||
0, 248, 8, 40, 48, 32, 32, 64, 5, 7, 7, 6, 0, 0, 8, 16,
|
0, 248, 8, 40, 48, 32, 32, 64, 5, 7, 7, 6, 0, 0, 8, 16,
|
||||||
32, 96, 160, 32, 32, 5, 7, 7, 6, 0, 0, 32, 248, 136, 136, 8,
|
32, 96, 160, 32, 32, 5, 7, 7, 6, 0, 0, 32, 248, 136, 136, 8,
|
||||||
16, 32, 5, 6, 6, 6, 0, 0, 248, 32, 32, 32, 32, 248, 5, 7,
|
16, 32, 5, 6, 6, 6, 0, 0, 248, 32, 32, 32, 32, 248, 5, 7,
|
||||||
|
@ -124,47 +146,47 @@ const u8g_fntpgm_uint8_t HD44780_J_5x7[2491] U8G_SECTION(".progmem.HD44780_J_5x7
|
||||||
6, 0, 0, 112, 0, 248, 32, 32, 32, 64, 3, 7, 7, 6, 1, 0,
|
6, 0, 0, 112, 0, 248, 32, 32, 32, 64, 3, 7, 7, 6, 1, 0,
|
||||||
128, 128, 128, 192, 160, 128, 128, 5, 7, 7, 6, 0, 0, 32, 32, 248,
|
128, 128, 128, 192, 160, 128, 128, 5, 7, 7, 6, 0, 0, 32, 32, 248,
|
||||||
32, 32, 64, 128, 5, 6, 6, 6, 0, 0, 112, 0, 0, 0, 0, 248,
|
32, 32, 64, 128, 5, 6, 6, 6, 0, 0, 112, 0, 0, 0, 0, 248,
|
||||||
5, 6, 6, 6, 0, 0, 248, 8, 80, 32, 80, 128, 5, 6, 6, 6,
|
5, 6, 6, 6, 0, 0, 248, 8, 80, 32, 80, 128, 5, 7, 7, 6,
|
||||||
0, 1, 32, 248, 16, 32, 112, 168, 3, 7, 7, 6, 1, 0, 32, 32,
|
0, 0, 32, 248, 16, 32, 112, 168, 32, 3, 7, 7, 6, 1, 0, 32,
|
||||||
32, 32, 32, 64, 128, 5, 6, 6, 6, 0, 0, 32, 16, 136, 136, 136,
|
32, 32, 32, 32, 64, 128, 5, 6, 6, 6, 0, 0, 32, 16, 136, 136,
|
||||||
136, 5, 7, 7, 6, 0, 0, 128, 128, 248, 128, 128, 128, 120, 5, 6,
|
136, 136, 5, 7, 7, 6, 0, 0, 128, 128, 248, 128, 128, 128, 120, 5,
|
||||||
6, 6, 0, 0, 248, 8, 8, 8, 16, 96, 5, 5, 5, 6, 0, 1,
|
6, 6, 6, 0, 0, 248, 8, 8, 8, 16, 96, 5, 5, 5, 6, 0,
|
||||||
64, 160, 16, 8, 8, 5, 7, 7, 6, 0, 0, 32, 248, 32, 32, 168,
|
1, 64, 160, 16, 8, 8, 5, 7, 7, 6, 0, 0, 32, 248, 32, 32,
|
||||||
168, 32, 5, 6, 6, 6, 0, 0, 248, 8, 8, 80, 32, 16, 4, 6,
|
168, 168, 32, 5, 6, 6, 6, 0, 0, 248, 8, 8, 80, 32, 16, 4,
|
||||||
6, 6, 1, 0, 224, 0, 224, 0, 224, 16, 5, 6, 6, 6, 0, 0,
|
6, 6, 6, 1, 0, 224, 0, 224, 0, 224, 16, 5, 6, 6, 6, 0,
|
||||||
32, 64, 128, 136, 248, 8, 5, 6, 6, 6, 0, 0, 8, 8, 80, 32,
|
0, 32, 64, 128, 136, 248, 8, 5, 6, 6, 6, 0, 0, 8, 8, 80,
|
||||||
80, 128, 5, 6, 6, 6, 0, 0, 248, 64, 248, 64, 64, 56, 5, 7,
|
32, 80, 128, 5, 6, 6, 6, 0, 0, 248, 64, 248, 64, 64, 56, 5,
|
||||||
7, 6, 0, 0, 64, 64, 248, 72, 80, 64, 64, 5, 7, 7, 6, 0,
|
7, 7, 6, 0, 0, 64, 64, 248, 72, 80, 64, 64, 5, 7, 7, 6,
|
||||||
0, 112, 16, 16, 16, 16, 16, 248, 5, 6, 6, 6, 0, 0, 248, 8,
|
0, 0, 112, 16, 16, 16, 16, 16, 248, 5, 6, 6, 6, 0, 0, 248,
|
||||||
248, 8, 8, 248, 5, 7, 7, 6, 0, 0, 112, 0, 248, 8, 8, 16,
|
8, 248, 8, 8, 248, 5, 7, 7, 6, 0, 0, 112, 0, 248, 8, 8,
|
||||||
32, 4, 7, 7, 6, 0, 0, 144, 144, 144, 144, 16, 32, 64, 5, 6,
|
16, 32, 4, 7, 7, 6, 0, 0, 144, 144, 144, 144, 16, 32, 64, 5,
|
||||||
6, 6, 0, 0, 32, 160, 160, 168, 168, 176, 5, 7, 7, 6, 0, 0,
|
6, 6, 6, 0, 0, 32, 160, 160, 168, 168, 176, 5, 7, 7, 6, 0,
|
||||||
128, 128, 128, 136, 144, 160, 192, 5, 6, 6, 6, 0, 0, 248, 136, 136,
|
0, 128, 128, 128, 136, 144, 160, 192, 5, 6, 6, 6, 0, 0, 248, 136,
|
||||||
136, 136, 248, 5, 6, 6, 6, 0, 0, 248, 136, 136, 8, 16, 32, 5,
|
136, 136, 136, 248, 5, 6, 6, 6, 0, 0, 248, 136, 136, 8, 16, 32,
|
||||||
6, 6, 6, 0, 0, 192, 0, 8, 8, 16, 224, 4, 3, 3, 6, 0,
|
5, 6, 6, 6, 0, 0, 192, 0, 8, 8, 16, 224, 4, 3, 3, 6,
|
||||||
4, 32, 144, 64, 3, 3, 3, 6, 0, 4, 224, 160, 224, 5, 5, 5,
|
0, 4, 32, 144, 64, 3, 3, 3, 6, 0, 4, 224, 160, 224, 5, 5,
|
||||||
6, 0, 1, 72, 168, 144, 144, 104, 5, 7, 7, 6, 0, 0, 80, 0,
|
5, 6, 0, 1, 72, 168, 144, 144, 104, 5, 7, 7, 6, 0, 0, 80,
|
||||||
112, 8, 120, 136, 120, 4, 8, 8, 6, 1, 255, 96, 144, 144, 224, 144,
|
0, 112, 8, 120, 136, 120, 4, 8, 8, 6, 1, 255, 96, 144, 144, 224,
|
||||||
144, 224, 128, 5, 5, 5, 6, 0, 0, 112, 128, 96, 136, 112, 5, 6,
|
144, 144, 224, 128, 5, 5, 5, 6, 0, 0, 112, 128, 96, 136, 112, 5,
|
||||||
6, 6, 0, 255, 136, 136, 152, 232, 136, 128, 5, 5, 5, 6, 0, 0,
|
6, 6, 6, 0, 255, 136, 136, 152, 232, 136, 128, 5, 5, 5, 6, 0,
|
||||||
120, 160, 144, 136, 112, 5, 7, 7, 6, 0, 254, 48, 72, 136, 136, 240,
|
0, 120, 160, 144, 136, 112, 5, 7, 7, 6, 0, 254, 48, 72, 136, 136,
|
||||||
128, 128, 5, 8, 8, 6, 0, 254, 120, 136, 136, 136, 120, 8, 8, 112,
|
240, 128, 128, 5, 8, 8, 6, 0, 254, 120, 136, 136, 136, 120, 8, 8,
|
||||||
5, 5, 5, 6, 0, 1, 56, 32, 32, 160, 64, 4, 3, 3, 6, 0,
|
112, 5, 5, 5, 6, 0, 1, 56, 32, 32, 160, 64, 4, 3, 3, 6,
|
||||||
3, 16, 208, 16, 4, 8, 8, 6, 0, 255, 16, 0, 48, 16, 16, 16,
|
0, 3, 16, 208, 16, 4, 8, 8, 6, 0, 255, 16, 0, 48, 16, 16,
|
||||||
144, 96, 3, 3, 3, 6, 0, 4, 160, 64, 160, 5, 7, 7, 6, 0,
|
16, 144, 96, 3, 3, 3, 6, 0, 4, 160, 64, 160, 5, 7, 7, 6,
|
||||||
0, 32, 112, 160, 160, 168, 112, 32, 5, 7, 7, 6, 0, 0, 64, 64,
|
0, 0, 32, 112, 160, 160, 168, 112, 32, 5, 7, 7, 6, 0, 0, 64,
|
||||||
224, 64, 224, 64, 120, 5, 7, 7, 6, 0, 0, 112, 0, 176, 200, 136,
|
64, 224, 64, 224, 64, 120, 5, 7, 7, 6, 0, 0, 112, 0, 176, 200,
|
||||||
136, 136, 5, 7, 7, 6, 0, 0, 80, 0, 112, 136, 136, 136, 112, 5,
|
136, 136, 136, 5, 7, 7, 6, 0, 0, 80, 0, 112, 136, 136, 136, 112,
|
||||||
7, 7, 6, 0, 255, 176, 200, 136, 136, 240, 128, 128, 5, 7, 7, 6,
|
5, 7, 7, 6, 0, 255, 176, 200, 136, 136, 240, 128, 128, 5, 7, 7,
|
||||||
0, 255, 104, 152, 136, 136, 120, 8, 8, 5, 6, 6, 6, 0, 0, 112,
|
6, 0, 255, 104, 152, 136, 136, 120, 8, 8, 5, 6, 6, 6, 0, 0,
|
||||||
136, 248, 136, 136, 112, 5, 3, 3, 6, 0, 2, 88, 168, 208, 5, 5,
|
112, 136, 248, 136, 136, 112, 5, 3, 3, 6, 0, 2, 88, 168, 208, 5,
|
||||||
5, 6, 0, 0, 112, 136, 136, 80, 216, 5, 7, 7, 6, 0, 0, 80,
|
5, 5, 6, 0, 0, 112, 136, 136, 80, 216, 5, 7, 7, 6, 0, 0,
|
||||||
0, 136, 136, 136, 152, 104, 5, 7, 7, 6, 0, 0, 248, 128, 64, 32,
|
80, 0, 136, 136, 136, 152, 104, 5, 7, 7, 6, 0, 0, 248, 128, 64,
|
||||||
64, 128, 248, 5, 5, 5, 6, 0, 0, 248, 80, 80, 80, 152, 5, 7,
|
32, 64, 128, 248, 5, 5, 5, 6, 0, 0, 248, 80, 80, 80, 152, 5,
|
||||||
7, 6, 0, 0, 248, 0, 136, 80, 32, 80, 136, 5, 7, 7, 6, 0,
|
7, 7, 6, 0, 0, 248, 0, 136, 80, 32, 80, 136, 5, 7, 7, 6,
|
||||||
255, 136, 136, 136, 136, 120, 8, 112, 5, 6, 6, 6, 0, 1, 8, 240,
|
0, 255, 136, 136, 136, 136, 120, 8, 112, 5, 6, 6, 6, 0, 0, 8,
|
||||||
32, 248, 32, 32, 5, 5, 5, 6, 0, 0, 248, 64, 120, 72, 136, 5,
|
240, 32, 248, 32, 32, 5, 5, 5, 6, 0, 0, 248, 64, 120, 72, 136,
|
||||||
5, 5, 6, 0, 0, 248, 168, 248, 136, 136, 5, 5, 5, 6, 0, 1,
|
5, 5, 5, 6, 0, 0, 248, 168, 248, 136, 136, 5, 5, 5, 6, 0,
|
||||||
32, 0, 248, 0, 32, 0, 0, 0, 6, 0, 8, 6, 10, 10, 6, 0,
|
1, 32, 0, 248, 0, 32, 0, 0, 0, 6, 0, 0, 6, 10, 10, 6,
|
||||||
254, 252, 252, 252, 252, 252, 252, 252, 252, 252, 252
|
0, 254, 252, 252, 252, 252, 252, 252, 252, 252, 252, 252
|
||||||
};
|
};
|
||||||
|
|
|
@ -1,4 +1,26 @@
|
||||||
/*
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
Fontname: HD44780_W
|
Fontname: HD44780_W
|
||||||
Copyright: A.Hardtung, public domain
|
Copyright: A.Hardtung, public domain
|
||||||
Capital A Height: 7, '1' Height: 7
|
Capital A Height: 7, '1' Height: 7
|
||||||
|
|
|
@ -1,4 +1,26 @@
|
||||||
/*
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
Fontname: ISO10646-1
|
Fontname: ISO10646-1
|
||||||
Copyright: A.Hardtung, public domain
|
Copyright: A.Hardtung, public domain
|
||||||
Capital A Height: 7, '1' Height: 7
|
Capital A Height: 7, '1' Height: 7
|
||||||
|
|
|
@ -1,4 +1,26 @@
|
||||||
/*
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
Fontname: ISO10646_5_Cyrillic
|
Fontname: ISO10646_5_Cyrillic
|
||||||
Copyright: A. Hardtung, public domain
|
Copyright: A. Hardtung, public domain
|
||||||
Capital A Height: 7, '1' Height: 7
|
Capital A Height: 7, '1' Height: 7
|
||||||
|
|
|
@ -1,4 +1,26 @@
|
||||||
/*
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
Fontname: ISO10646_CN
|
Fontname: ISO10646_CN
|
||||||
Copyright: A. Hardtung, public domain
|
Copyright: A. Hardtung, public domain
|
||||||
Capital A Height: 7, '1' Height: 7
|
Capital A Height: 7, '1' Height: 7
|
||||||
|
|
|
@ -1,8 +1,30 @@
|
||||||
/*
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
Fontname: ISO10646_Kana
|
Fontname: ISO10646_Kana
|
||||||
Copyright: A. Hardtung, public domain
|
Copyright: A. Hardtung, public domain
|
||||||
Capital A Height: 7, '1' Height: 7
|
Capital A Height: 7, '1' Height: 7
|
||||||
Calculated Max Values w= 5 h= 9 x= 2 y= 5 dx= 6 dy= 0 ascent= 8 len= 9
|
Calculated Max Values w= 5 h= 8 x= 2 y= 5 dx= 6 dy= 0 ascent= 8 len= 8
|
||||||
Font Bounding box w= 6 h= 9 x= 0 y=-2
|
Font Bounding box w= 6 h= 9 x= 0 y=-2
|
||||||
Calculated Min Values x= 0 y=-1 dx= 0 dy= 0
|
Calculated Min Values x= 0 y=-1 dx= 0 dy= 0
|
||||||
Pure Font ascent = 7 descent=-1
|
Pure Font ascent = 7 descent=-1
|
||||||
|
@ -10,7 +32,7 @@
|
||||||
Max Font ascent = 8 descent=-1
|
Max Font ascent = 8 descent=-1
|
||||||
*/
|
*/
|
||||||
#include <U8glib.h>
|
#include <U8glib.h>
|
||||||
const u8g_fntpgm_uint8_t ISO10646_Kana_5x7[2549] U8G_SECTION(".progmem.ISO10646_Kana_5x7") = {
|
const u8g_fntpgm_uint8_t ISO10646_Kana_5x7[2482] U8G_SECTION(".progmem.ISO10646_Kana_5x7") = {
|
||||||
0, 6, 9, 0, 254, 7, 1, 145, 3, 32, 32, 255, 255, 8, 255, 7,
|
0, 6, 9, 0, 254, 7, 1, 145, 3, 32, 32, 255, 255, 8, 255, 7,
|
||||||
255, 0, 0, 0, 6, 0, 0, 1, 7, 7, 6, 2, 0, 128, 128, 128,
|
255, 0, 0, 0, 6, 0, 0, 1, 7, 7, 6, 2, 0, 128, 128, 128,
|
||||||
128, 128, 0, 128, 3, 2, 2, 6, 1, 5, 160, 160, 5, 7, 7, 6,
|
128, 128, 0, 128, 3, 2, 2, 6, 1, 5, 160, 160, 5, 7, 7, 6,
|
||||||
|
@ -95,80 +117,76 @@ const u8g_fntpgm_uint8_t ISO10646_Kana_5x7[2549] U8G_SECTION(".progmem.ISO10646_
|
||||||
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0,
|
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0,
|
||||||
0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6,
|
0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6,
|
||||||
0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0,
|
0, 0, 0, 0, 0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 0, 0,
|
||||||
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 5, 3, 3, 6, 0, 2,
|
0, 6, 0, 0, 0, 0, 0, 6, 0, 0, 5, 3, 3, 6, 0, 1,
|
||||||
248, 0, 248, 5, 6, 6, 6, 0, 0, 248, 8, 40, 48, 32, 64, 5,
|
248, 0, 248, 4, 4, 4, 6, 0, 0, 240, 16, 96, 64, 5, 6, 6,
|
||||||
7, 7, 6, 0, 0, 248, 8, 40, 48, 32, 32, 64, 4, 5, 5, 6,
|
6, 0, 0, 248, 8, 40, 48, 32, 64, 3, 4, 4, 6, 1, 0, 32,
|
||||||
0, 0, 16, 32, 96, 160, 32, 5, 7, 7, 6, 0, 0, 8, 16, 32,
|
64, 192, 64, 4, 6, 6, 6, 0, 0, 16, 32, 96, 160, 32, 32, 4,
|
||||||
96, 160, 32, 32, 5, 5, 5, 6, 0, 0, 32, 248, 136, 8, 48, 5,
|
4, 4, 6, 0, 0, 32, 240, 144, 32, 5, 6, 6, 6, 0, 0, 32,
|
||||||
7, 7, 6, 0, 0, 32, 248, 136, 136, 8, 16, 32, 5, 4, 4, 6,
|
248, 136, 8, 16, 32, 3, 4, 4, 6, 1, 0, 224, 64, 64, 224, 5,
|
||||||
0, 0, 248, 32, 32, 248, 5, 6, 6, 6, 0, 0, 248, 32, 32, 32,
|
5, 5, 6, 0, 0, 248, 32, 32, 32, 248, 4, 4, 4, 6, 0, 0,
|
||||||
32, 248, 5, 5, 5, 6, 0, 0, 16, 248, 48, 80, 144, 5, 7, 7,
|
32, 240, 96, 160, 5, 6, 6, 6, 0, 0, 16, 248, 48, 80, 144, 16,
|
||||||
6, 0, 0, 16, 248, 16, 48, 80, 144, 16, 5, 5, 5, 6, 0, 0,
|
5, 6, 6, 6, 0, 0, 64, 248, 72, 72, 72, 144, 5, 8, 8, 6,
|
||||||
64, 248, 72, 80, 64, 5, 7, 7, 6, 0, 0, 40, 0, 64, 248, 72,
|
0, 0, 40, 0, 64, 248, 72, 72, 72, 144, 5, 6, 6, 6, 0, 0,
|
||||||
80, 64, 5, 7, 7, 6, 0, 0, 32, 248, 32, 248, 32, 32, 32, 5,
|
32, 248, 32, 248, 32, 32, 5, 8, 8, 6, 0, 0, 40, 0, 32, 248,
|
||||||
8, 8, 6, 0, 0, 40, 0, 32, 248, 32, 248, 32, 32, 4, 6, 6,
|
32, 248, 32, 32, 4, 5, 5, 6, 0, 0, 112, 144, 16, 32, 192, 5,
|
||||||
6, 0, 0, 64, 112, 144, 16, 16, 32, 5, 8, 8, 6, 0, 0, 40,
|
7, 7, 6, 0, 0, 40, 0, 112, 144, 16, 32, 192, 5, 6, 6, 6,
|
||||||
0, 64, 112, 144, 16, 16, 32, 5, 6, 6, 6, 0, 0, 64, 120, 144,
|
0, 0, 64, 120, 144, 16, 16, 32, 5, 8, 8, 6, 0, 0, 40, 0,
|
||||||
16, 16, 32, 5, 8, 8, 6, 0, 0, 40, 0, 64, 120, 144, 16, 16,
|
64, 120, 144, 16, 16, 32, 5, 5, 5, 6, 0, 0, 248, 8, 8, 8,
|
||||||
32, 5, 5, 5, 6, 0, 0, 248, 8, 8, 8, 248, 5, 7, 7, 6,
|
248, 5, 7, 7, 6, 0, 0, 40, 0, 248, 8, 8, 8, 248, 5, 6,
|
||||||
0, 0, 40, 0, 248, 8, 8, 8, 248, 5, 7, 7, 6, 0, 255, 80,
|
6, 6, 0, 0, 80, 248, 80, 16, 32, 64, 5, 8, 8, 6, 0, 0,
|
||||||
248, 80, 80, 16, 32, 64, 5, 9, 9, 6, 0, 255, 40, 0, 80, 248,
|
40, 0, 80, 248, 80, 16, 32, 64, 5, 5, 5, 6, 0, 0, 192, 8,
|
||||||
80, 80, 16, 32, 64, 5, 6, 6, 6, 0, 0, 192, 8, 200, 8, 16,
|
200, 16, 224, 5, 7, 7, 6, 0, 0, 40, 0, 192, 8, 200, 16, 224,
|
||||||
224, 5, 8, 8, 6, 0, 0, 40, 0, 192, 8, 200, 8, 16, 224, 5,
|
5, 5, 5, 6, 0, 0, 248, 16, 32, 80, 136, 5, 7, 7, 6, 0,
|
||||||
6, 6, 6, 0, 0, 248, 8, 16, 32, 80, 136, 5, 8, 8, 6, 0,
|
0, 40, 0, 248, 16, 32, 80, 136, 5, 6, 6, 6, 0, 0, 64, 248,
|
||||||
0, 40, 0, 248, 8, 16, 32, 80, 136, 5, 6, 6, 6, 0, 0, 64,
|
72, 80, 64, 56, 5, 8, 8, 6, 0, 0, 40, 0, 64, 248, 72, 80,
|
||||||
248, 72, 80, 64, 120, 5, 8, 8, 6, 0, 0, 40, 0, 64, 248, 72,
|
64, 56, 5, 5, 5, 6, 0, 0, 136, 136, 72, 16, 96, 5, 7, 7,
|
||||||
80, 64, 120, 4, 4, 4, 6, 0, 1, 16, 208, 16, 224, 5, 7, 7,
|
6, 0, 0, 40, 0, 136, 136, 72, 16, 96, 5, 5, 5, 6, 0, 0,
|
||||||
6, 0, 0, 40, 0, 8, 200, 8, 16, 224, 5, 7, 7, 6, 0, 255,
|
120, 72, 168, 16, 96, 5, 7, 7, 6, 0, 0, 40, 0, 120, 72, 168,
|
||||||
32, 120, 136, 40, 16, 40, 64, 5, 9, 9, 6, 0, 255, 40, 0, 32,
|
16, 96, 5, 6, 6, 6, 0, 0, 16, 224, 32, 248, 32, 64, 5, 8,
|
||||||
120, 136, 40, 16, 40, 64, 5, 6, 6, 6, 0, 0, 240, 32, 248, 32,
|
8, 6, 0, 0, 40, 0, 16, 224, 32, 248, 32, 64, 5, 4, 4, 6,
|
||||||
64, 128, 5, 8, 8, 6, 0, 0, 40, 0, 240, 32, 248, 32, 64, 128,
|
0, 0, 168, 168, 8, 48, 5, 5, 5, 6, 0, 0, 168, 168, 8, 16,
|
||||||
4, 5, 5, 6, 0, 1, 192, 16, 208, 16, 224, 5, 6, 6, 6, 0,
|
32, 5, 7, 7, 6, 0, 0, 40, 0, 168, 168, 8, 16, 32, 5, 6,
|
||||||
0, 192, 8, 200, 8, 16, 224, 5, 8, 8, 6, 0, 0, 40, 0, 192,
|
6, 6, 0, 0, 112, 0, 248, 32, 32, 64, 5, 8, 8, 6, 0, 0,
|
||||||
8, 200, 8, 16, 224, 5, 6, 6, 6, 0, 0, 112, 0, 248, 32, 32,
|
40, 0, 112, 0, 248, 32, 32, 64, 3, 6, 6, 6, 1, 0, 128, 128,
|
||||||
64, 5, 8, 8, 6, 0, 0, 40, 0, 112, 0, 248, 32, 32, 64, 3,
|
192, 160, 128, 128, 4, 8, 8, 6, 1, 0, 80, 0, 128, 128, 192, 160,
|
||||||
7, 7, 6, 1, 0, 128, 128, 128, 192, 160, 128, 128, 4, 8, 8, 6,
|
128, 128, 5, 6, 6, 6, 0, 0, 32, 248, 32, 32, 64, 128, 5, 5,
|
||||||
1, 0, 80, 0, 128, 128, 192, 160, 128, 128, 5, 7, 7, 6, 0, 0,
|
5, 6, 0, 0, 112, 0, 0, 0, 248, 5, 5, 5, 6, 0, 0, 248,
|
||||||
32, 32, 248, 32, 32, 64, 128, 5, 6, 6, 6, 0, 0, 112, 0, 0,
|
8, 80, 32, 208, 5, 6, 6, 6, 0, 0, 32, 248, 16, 32, 112, 168,
|
||||||
0, 0, 248, 5, 6, 6, 6, 0, 0, 248, 8, 80, 32, 80, 128, 5,
|
3, 6, 6, 6, 1, 0, 32, 32, 32, 32, 64, 128, 5, 5, 5, 6,
|
||||||
7, 7, 6, 0, 255, 32, 248, 8, 16, 32, 112, 168, 3, 7, 7, 6,
|
0, 0, 16, 136, 136, 136, 136, 5, 7, 7, 6, 0, 0, 40, 0, 16,
|
||||||
1, 0, 32, 32, 32, 32, 32, 64, 128, 5, 5, 5, 6, 0, 0, 16,
|
136, 136, 136, 136, 5, 8, 8, 6, 0, 0, 24, 24, 0, 16, 136, 136,
|
||||||
136, 136, 136, 136, 5, 7, 7, 6, 0, 0, 40, 0, 16, 136, 136, 136,
|
136, 136, 5, 6, 6, 6, 0, 0, 128, 128, 248, 128, 128, 120, 5, 7,
|
||||||
136, 5, 8, 8, 6, 0, 0, 24, 24, 0, 16, 136, 136, 136, 136, 5,
|
7, 6, 0, 0, 40, 128, 128, 248, 128, 128, 120, 5, 7, 7, 6, 0,
|
||||||
7, 7, 6, 0, 0, 128, 128, 248, 128, 128, 128, 120, 5, 8, 8, 6,
|
0, 24, 152, 128, 248, 128, 128, 120, 5, 5, 5, 6, 0, 0, 248, 8,
|
||||||
0, 0, 40, 128, 128, 248, 128, 128, 128, 120, 5, 8, 8, 6, 0, 0,
|
8, 16, 96, 5, 7, 7, 6, 0, 0, 40, 0, 248, 8, 8, 16, 96,
|
||||||
24, 152, 128, 248, 128, 128, 128, 120, 5, 6, 6, 6, 0, 0, 248, 8,
|
5, 8, 8, 6, 0, 0, 24, 24, 0, 248, 8, 8, 16, 96, 5, 4,
|
||||||
8, 8, 16, 96, 5, 8, 8, 6, 0, 0, 40, 0, 248, 8, 8, 8,
|
4, 6, 0, 1, 64, 160, 16, 8, 5, 6, 6, 6, 0, 1, 40, 0,
|
||||||
16, 96, 5, 8, 8, 6, 0, 0, 24, 24, 248, 8, 8, 8, 16, 96,
|
64, 160, 16, 8, 5, 6, 6, 6, 0, 1, 24, 24, 64, 160, 16, 8,
|
||||||
5, 5, 5, 6, 0, 1, 64, 160, 16, 8, 8, 5, 7, 7, 6, 0,
|
5, 6, 6, 6, 0, 0, 32, 248, 32, 168, 168, 32, 5, 8, 8, 6,
|
||||||
1, 40, 0, 64, 160, 16, 8, 8, 5, 7, 7, 6, 0, 1, 24, 24,
|
0, 0, 40, 0, 32, 248, 32, 168, 168, 32, 5, 8, 8, 6, 0, 0,
|
||||||
64, 160, 16, 8, 8, 5, 6, 6, 6, 0, 0, 32, 248, 32, 32, 168,
|
24, 24, 32, 248, 32, 168, 168, 32, 5, 5, 5, 6, 0, 0, 248, 8,
|
||||||
168, 5, 8, 8, 6, 0, 0, 40, 0, 32, 248, 32, 32, 168, 168, 5,
|
80, 32, 16, 4, 5, 5, 6, 1, 0, 224, 0, 224, 0, 240, 5, 5,
|
||||||
8, 8, 6, 0, 0, 24, 24, 32, 248, 32, 32, 168, 168, 5, 6, 6,
|
5, 6, 0, 0, 32, 64, 136, 248, 8, 5, 5, 5, 6, 0, 0, 8,
|
||||||
6, 0, 0, 248, 8, 8, 80, 32, 16, 4, 6, 6, 6, 1, 0, 224,
|
40, 16, 40, 192, 5, 5, 5, 6, 0, 0, 248, 64, 248, 64, 56, 5,
|
||||||
0, 224, 0, 224, 16, 5, 6, 6, 6, 0, 0, 32, 64, 128, 144, 248,
|
4, 4, 6, 0, 0, 64, 248, 80, 64, 5, 6, 6, 6, 0, 0, 64,
|
||||||
8, 5, 6, 6, 6, 0, 0, 8, 8, 80, 32, 80, 128, 5, 6, 6,
|
248, 72, 80, 64, 64, 4, 4, 4, 6, 0, 0, 96, 32, 32, 240, 5,
|
||||||
6, 0, 0, 120, 32, 248, 32, 32, 56, 5, 7, 7, 6, 0, 0, 64,
|
5, 5, 6, 0, 0, 112, 16, 16, 16, 248, 4, 5, 5, 6, 0, 0,
|
||||||
64, 248, 72, 80, 64, 64, 5, 7, 7, 6, 0, 0, 64, 248, 72, 80,
|
240, 16, 240, 16, 240, 5, 5, 5, 6, 0, 0, 248, 8, 248, 8, 248,
|
||||||
64, 64, 64, 5, 5, 5, 6, 0, 0, 112, 16, 16, 16, 248, 5, 7,
|
5, 6, 6, 6, 0, 0, 112, 0, 248, 8, 16, 32, 4, 6, 6, 6,
|
||||||
7, 6, 0, 0, 112, 16, 16, 16, 16, 16, 248, 4, 5, 5, 6, 1,
|
0, 0, 144, 144, 144, 144, 16, 32, 5, 5, 5, 6, 0, 0, 32, 160,
|
||||||
0, 240, 16, 240, 16, 240, 5, 7, 7, 6, 0, 0, 248, 8, 8, 248,
|
168, 168, 176, 4, 5, 5, 6, 0, 0, 128, 128, 144, 160, 192, 5, 5,
|
||||||
8, 8, 248, 5, 6, 6, 6, 0, 0, 112, 0, 248, 8, 16, 32, 3,
|
5, 6, 0, 0, 248, 136, 136, 136, 248, 4, 4, 4, 6, 0, 0, 240,
|
||||||
6, 6, 6, 1, 0, 160, 160, 160, 160, 32, 64, 5, 6, 6, 6, 0,
|
144, 16, 32, 5, 5, 5, 6, 0, 0, 248, 136, 8, 16, 32, 5, 6,
|
||||||
0, 80, 80, 80, 80, 88, 144, 4, 6, 6, 6, 1, 0, 128, 128, 128,
|
6, 6, 0, 0, 16, 248, 80, 80, 248, 16, 5, 5, 5, 6, 0, 0,
|
||||||
144, 160, 192, 5, 6, 6, 6, 0, 0, 248, 136, 136, 136, 248, 136, 5,
|
248, 8, 48, 32, 248, 5, 5, 5, 6, 0, 0, 248, 8, 248, 8, 48,
|
||||||
5, 5, 6, 0, 0, 248, 136, 8, 16, 96, 5, 6, 6, 6, 0, 0,
|
5, 5, 5, 6, 0, 0, 192, 8, 8, 16, 224, 5, 8, 8, 6, 0,
|
||||||
248, 136, 8, 8, 16, 96, 5, 6, 6, 6, 0, 0, 16, 248, 80, 80,
|
0, 40, 0, 32, 248, 136, 8, 16, 32, 4, 4, 4, 6, 0, 0, 64,
|
||||||
248, 16, 5, 6, 6, 6, 0, 0, 248, 8, 80, 96, 64, 248, 5, 6,
|
240, 80, 160, 4, 4, 4, 6, 0, 0, 64, 240, 32, 64, 5, 7, 7,
|
||||||
6, 6, 0, 0, 248, 8, 248, 8, 16, 32, 5, 6, 6, 6, 0, 0,
|
6, 0, 0, 40, 0, 248, 136, 8, 16, 96, 5, 8, 8, 6, 0, 0,
|
||||||
128, 64, 8, 8, 16, 224, 5, 8, 8, 6, 0, 0, 40, 0, 32, 248,
|
40, 0, 16, 248, 80, 80, 248, 16, 5, 7, 7, 6, 0, 0, 40, 0,
|
||||||
136, 8, 24, 32, 5, 6, 6, 6, 0, 0, 64, 248, 72, 72, 136, 144,
|
248, 8, 48, 32, 248, 5, 7, 7, 6, 0, 0, 40, 0, 248, 8, 248,
|
||||||
4, 5, 5, 6, 1, 0, 128, 240, 160, 32, 32, 5, 8, 8, 6, 0,
|
8, 48, 2, 2, 2, 6, 2, 2, 192, 192, 5, 1, 1, 6, 0, 2,
|
||||||
0, 40, 0, 248, 136, 8, 8, 16, 96, 5, 8, 8, 6, 0, 0, 40,
|
248, 5, 4, 4, 6, 0, 1, 128, 96, 16, 8, 5, 5, 5, 6, 0,
|
||||||
0, 16, 248, 80, 80, 248, 16, 5, 7, 7, 6, 0, 0, 40, 0, 248,
|
1, 40, 128, 96, 16, 8, 5, 6, 6, 6, 0, 0, 248, 8, 8, 8,
|
||||||
16, 32, 32, 248, 5, 8, 8, 6, 0, 0, 40, 0, 248, 8, 248, 8,
|
8, 8
|
||||||
16, 32, 2, 2, 2, 6, 2, 2, 192, 192, 5, 1, 1, 6, 0, 3,
|
|
||||||
248, 5, 5, 5, 6, 0, 1, 128, 64, 32, 16, 8, 5, 6, 6, 6,
|
|
||||||
0, 1, 40, 128, 64, 32, 16, 8, 5, 7, 7, 6, 0, 0, 248, 8,
|
|
||||||
8, 8, 8, 8, 8
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -1,4 +1,26 @@
|
||||||
/*
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
Fontname: Marlin_symbols
|
Fontname: Marlin_symbols
|
||||||
Copyright: Created with Fony 1.4.7
|
Copyright: Created with Fony 1.4.7
|
||||||
Capital A Height: 0, '1' Height: 0
|
Capital A Height: 0, '1' Height: 0
|
||||||
|
|
|
@ -1,3 +1,25 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* dogm_lcd_implementation.h
|
* dogm_lcd_implementation.h
|
||||||
*
|
*
|
||||||
|
@ -7,7 +29,7 @@
|
||||||
*
|
*
|
||||||
* With the use of:
|
* With the use of:
|
||||||
* u8glib by Oliver Kraus
|
* u8glib by Oliver Kraus
|
||||||
* http://code.google.com/p/u8glib/
|
* https://github.com/olikraus/U8glib_Arduino
|
||||||
* License: http://opensource.org/licenses/BSD-3-Clause
|
* License: http://opensource.org/licenses/BSD-3-Clause
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
@ -22,9 +44,9 @@
|
||||||
#define BLEN_A 0
|
#define BLEN_A 0
|
||||||
#define BLEN_B 1
|
#define BLEN_B 1
|
||||||
#define BLEN_C 2
|
#define BLEN_C 2
|
||||||
#define EN_A BIT(BLEN_A)
|
#define EN_A (_BV(BLEN_A))
|
||||||
#define EN_B BIT(BLEN_B)
|
#define EN_B (_BV(BLEN_B))
|
||||||
#define EN_C BIT(BLEN_C)
|
#define EN_C (_BV(BLEN_C))
|
||||||
#define LCD_CLICKED (buttons&EN_C)
|
#define LCD_CLICKED (buttons&EN_C)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -146,7 +168,6 @@
|
||||||
#include "utf_mapper.h"
|
#include "utf_mapper.h"
|
||||||
|
|
||||||
int lcd_contrast;
|
int lcd_contrast;
|
||||||
static unsigned char blink = 0; // Variable for visualization of fan rotation in GLCD
|
|
||||||
static char currentfont = 0;
|
static char currentfont = 0;
|
||||||
|
|
||||||
static void lcd_setFont(char font_nr) {
|
static void lcd_setFont(char font_nr) {
|
||||||
|
@ -170,7 +191,7 @@ char lcd_print(char c) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
char lcd_print(char* str) {
|
char lcd_print(const char* str) {
|
||||||
char c;
|
char c;
|
||||||
int i = 0;
|
int i = 0;
|
||||||
char n = 0;
|
char n = 0;
|
||||||
|
@ -225,14 +246,14 @@ static void lcd_implementation_init() {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(SHOW_BOOTSCREEN)
|
#if ENABLED(SHOW_BOOTSCREEN)
|
||||||
int offx = (u8g.getWidth() - START_BMPWIDTH) / 2;
|
int offx = (u8g.getWidth() - (START_BMPWIDTH)) / 2;
|
||||||
#if ENABLED(START_BMPHIGH)
|
#if ENABLED(START_BMPHIGH)
|
||||||
int offy = 0;
|
int offy = 0;
|
||||||
#else
|
#else
|
||||||
int offy = DOG_CHAR_HEIGHT;
|
int offy = DOG_CHAR_HEIGHT;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
int txt1X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE1) - 1) * DOG_CHAR_WIDTH) / 2;
|
int txt1X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE1) - 1) * (DOG_CHAR_WIDTH)) / 2;
|
||||||
|
|
||||||
u8g.firstPage();
|
u8g.firstPage();
|
||||||
do {
|
do {
|
||||||
|
@ -240,11 +261,11 @@ static void lcd_implementation_init() {
|
||||||
u8g.drawBitmapP(offx, offy, START_BMPBYTEWIDTH, START_BMPHEIGHT, start_bmp);
|
u8g.drawBitmapP(offx, offy, START_BMPBYTEWIDTH, START_BMPHEIGHT, start_bmp);
|
||||||
lcd_setFont(FONT_MENU);
|
lcd_setFont(FONT_MENU);
|
||||||
#ifndef STRING_SPLASH_LINE2
|
#ifndef STRING_SPLASH_LINE2
|
||||||
u8g.drawStr(txt1X, u8g.getHeight() - DOG_CHAR_HEIGHT, STRING_SPLASH_LINE1);
|
u8g.drawStr(txt1X, u8g.getHeight() - (DOG_CHAR_HEIGHT), STRING_SPLASH_LINE1);
|
||||||
#else
|
#else
|
||||||
int txt2X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE2) - 1) * DOG_CHAR_WIDTH) / 2;
|
int txt2X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE2) - 1) * (DOG_CHAR_WIDTH)) / 2;
|
||||||
u8g.drawStr(txt1X, u8g.getHeight() - DOG_CHAR_HEIGHT * 3 / 2, STRING_SPLASH_LINE1);
|
u8g.drawStr(txt1X, u8g.getHeight() - (DOG_CHAR_HEIGHT) * 3 / 2, STRING_SPLASH_LINE1);
|
||||||
u8g.drawStr(txt2X, u8g.getHeight() - DOG_CHAR_HEIGHT * 1 / 2, STRING_SPLASH_LINE2);
|
u8g.drawStr(txt2X, u8g.getHeight() - (DOG_CHAR_HEIGHT) * 1 / 2, STRING_SPLASH_LINE2);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
} while (u8g.nextPage());
|
} while (u8g.nextPage());
|
||||||
|
@ -270,7 +291,7 @@ static void _draw_heater_status(int x, int heater) {
|
||||||
lcd_print(itostr3(int(heater >= 0 ? degHotend(heater) : degBed()) + 0.5));
|
lcd_print(itostr3(int(heater >= 0 ? degHotend(heater) : degBed()) + 0.5));
|
||||||
|
|
||||||
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
||||||
if (!isHeatingHotend(0)) {
|
if (heater >= 0 ? !isHeatingHotend(heater) : !isHeatingBed()) {
|
||||||
u8g.drawBox(x+7,y,2,2);
|
u8g.drawBox(x+7,y,2,2);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
@ -283,30 +304,39 @@ static void _draw_heater_status(int x, int heater) {
|
||||||
static void lcd_implementation_status_screen() {
|
static void lcd_implementation_status_screen() {
|
||||||
u8g.setColorIndex(1); // black on white
|
u8g.setColorIndex(1); // black on white
|
||||||
|
|
||||||
|
bool blink = lcd_blink();
|
||||||
|
|
||||||
// Symbols menu graphics, animated fan
|
// Symbols menu graphics, animated fan
|
||||||
u8g.drawBitmapP(9,1,STATUS_SCREENBYTEWIDTH,STATUS_SCREENHEIGHT, (blink % 2) && fanSpeed ? status_screen0_bmp : status_screen1_bmp);
|
u8g.drawBitmapP(9, 1, STATUS_SCREENBYTEWIDTH, STATUS_SCREENHEIGHT,
|
||||||
|
#if HAS_FAN0
|
||||||
|
blink && fanSpeeds[0] ? status_screen0_bmp : status_screen1_bmp
|
||||||
|
#else
|
||||||
|
status_screen0_bmp
|
||||||
|
#endif
|
||||||
|
);
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
// SD Card Symbol
|
// SD Card Symbol
|
||||||
u8g.drawBox(42, 42 - TALL_FONT_CORRECTION, 8, 7);
|
u8g.drawBox(42, 42 - (TALL_FONT_CORRECTION), 8, 7);
|
||||||
u8g.drawBox(50, 44 - TALL_FONT_CORRECTION, 2, 5);
|
u8g.drawBox(50, 44 - (TALL_FONT_CORRECTION), 2, 5);
|
||||||
u8g.drawFrame(42, 49 - TALL_FONT_CORRECTION, 10, 4);
|
u8g.drawFrame(42, 49 - (TALL_FONT_CORRECTION), 10, 4);
|
||||||
u8g.drawPixel(50, 43 - TALL_FONT_CORRECTION);
|
u8g.drawPixel(50, 43 - (TALL_FONT_CORRECTION));
|
||||||
|
|
||||||
// Progress bar frame
|
// Progress bar frame
|
||||||
u8g.drawFrame(54, 49, 73, 4 - TALL_FONT_CORRECTION);
|
u8g.drawFrame(54, 49, 73, 4 - (TALL_FONT_CORRECTION));
|
||||||
|
|
||||||
// SD Card Progress bar and clock
|
// SD Card Progress bar and clock
|
||||||
lcd_setFont(FONT_STATUSMENU);
|
lcd_setFont(FONT_STATUSMENU);
|
||||||
|
|
||||||
if (IS_SD_PRINTING) {
|
if (IS_SD_PRINTING) {
|
||||||
// Progress bar solid part
|
// Progress bar solid part
|
||||||
u8g.drawBox(55, 50, (unsigned int)(71.f * card.percentDone() / 100.f), 2 - TALL_FONT_CORRECTION);
|
u8g.drawBox(55, 50, (unsigned int)(71.f * card.percentDone() / 100.f), 2 - (TALL_FONT_CORRECTION));
|
||||||
}
|
}
|
||||||
|
|
||||||
u8g.setPrintPos(80,48);
|
u8g.setPrintPos(80,48);
|
||||||
if (print_job_start_ms != 0) {
|
if (print_job_start_ms != 0) {
|
||||||
uint16_t time = (millis() - print_job_start_ms) / 60000;
|
uint16_t time = (((print_job_stop_ms > print_job_start_ms)
|
||||||
|
? print_job_stop_ms : millis()) - print_job_start_ms) / 60000;
|
||||||
lcd_print(itostr2(time/60));
|
lcd_print(itostr2(time/60));
|
||||||
lcd_print(':');
|
lcd_print(':');
|
||||||
lcd_print(itostr2(time%60));
|
lcd_print(itostr2(time%60));
|
||||||
|
@ -325,8 +355,8 @@ static void lcd_implementation_status_screen() {
|
||||||
// Fan
|
// Fan
|
||||||
lcd_setFont(FONT_STATUSMENU);
|
lcd_setFont(FONT_STATUSMENU);
|
||||||
u8g.setPrintPos(104, 27);
|
u8g.setPrintPos(104, 27);
|
||||||
#if HAS_FAN
|
#if HAS_FAN0
|
||||||
int per = ((fanSpeed + 1) * 100) / 256;
|
int per = ((fanSpeeds[0] + 1) * 100) / 256;
|
||||||
if (per) {
|
if (per) {
|
||||||
lcd_print(itostr3(per));
|
lcd_print(itostr3(per));
|
||||||
lcd_print('%');
|
lcd_print('%');
|
||||||
|
@ -338,6 +368,9 @@ static void lcd_implementation_status_screen() {
|
||||||
}
|
}
|
||||||
|
|
||||||
// X, Y, Z-Coordinates
|
// X, Y, Z-Coordinates
|
||||||
|
// Before homing the axis letters are blinking 'X' <-> '?'.
|
||||||
|
// When axis is homed but axis_known_position is false the axis letters are blinking 'X' <-> ' '.
|
||||||
|
// When everything is ok you see a constant 'X'.
|
||||||
#define XYZ_BASELINE 38
|
#define XYZ_BASELINE 38
|
||||||
lcd_setFont(FONT_STATUSMENU);
|
lcd_setFont(FONT_STATUSMENU);
|
||||||
|
|
||||||
|
@ -348,32 +381,64 @@ static void lcd_implementation_status_screen() {
|
||||||
#endif
|
#endif
|
||||||
u8g.setColorIndex(0); // white on black
|
u8g.setColorIndex(0); // white on black
|
||||||
u8g.setPrintPos(2, XYZ_BASELINE);
|
u8g.setPrintPos(2, XYZ_BASELINE);
|
||||||
lcd_print('X');
|
if (blink)
|
||||||
|
lcd_printPGM(PSTR(MSG_X));
|
||||||
|
else {
|
||||||
|
if (!axis_homed[X_AXIS])
|
||||||
|
lcd_printPGM(PSTR("?"));
|
||||||
|
else {
|
||||||
|
#if DISABLED(DISABLE_REDUCED_ACCURACY_WARNING)
|
||||||
|
if (!axis_known_position[X_AXIS])
|
||||||
|
lcd_printPGM(PSTR(" "));
|
||||||
|
else
|
||||||
|
#endif
|
||||||
|
lcd_printPGM(PSTR(MSG_X));
|
||||||
|
}
|
||||||
|
}
|
||||||
u8g.drawPixel(8, XYZ_BASELINE - 5);
|
u8g.drawPixel(8, XYZ_BASELINE - 5);
|
||||||
u8g.drawPixel(8, XYZ_BASELINE - 3);
|
u8g.drawPixel(8, XYZ_BASELINE - 3);
|
||||||
u8g.setPrintPos(10, XYZ_BASELINE);
|
u8g.setPrintPos(10, XYZ_BASELINE);
|
||||||
if (axis_known_position[X_AXIS])
|
lcd_print(ftostr31ns(current_position[X_AXIS]));
|
||||||
lcd_print(ftostr31ns(current_position[X_AXIS]));
|
|
||||||
else
|
|
||||||
lcd_printPGM(PSTR("---"));
|
|
||||||
u8g.setPrintPos(43, XYZ_BASELINE);
|
u8g.setPrintPos(43, XYZ_BASELINE);
|
||||||
lcd_print('Y');
|
if (blink)
|
||||||
|
lcd_printPGM(PSTR(MSG_Y));
|
||||||
|
else {
|
||||||
|
if (!axis_homed[Y_AXIS])
|
||||||
|
lcd_printPGM(PSTR("?"));
|
||||||
|
else {
|
||||||
|
#if DISABLED(DISABLE_REDUCED_ACCURACY_WARNING)
|
||||||
|
if (!axis_known_position[Y_AXIS])
|
||||||
|
lcd_printPGM(PSTR(" "));
|
||||||
|
else
|
||||||
|
#endif
|
||||||
|
lcd_printPGM(PSTR(MSG_Y));
|
||||||
|
}
|
||||||
|
}
|
||||||
u8g.drawPixel(49, XYZ_BASELINE - 5);
|
u8g.drawPixel(49, XYZ_BASELINE - 5);
|
||||||
u8g.drawPixel(49, XYZ_BASELINE - 3);
|
u8g.drawPixel(49, XYZ_BASELINE - 3);
|
||||||
u8g.setPrintPos(51, XYZ_BASELINE);
|
u8g.setPrintPos(51, XYZ_BASELINE);
|
||||||
if (axis_known_position[Y_AXIS])
|
lcd_print(ftostr31ns(current_position[Y_AXIS]));
|
||||||
lcd_print(ftostr31ns(current_position[Y_AXIS]));
|
|
||||||
else
|
|
||||||
lcd_printPGM(PSTR("---"));
|
|
||||||
u8g.setPrintPos(83, XYZ_BASELINE);
|
u8g.setPrintPos(83, XYZ_BASELINE);
|
||||||
lcd_print('Z');
|
if (blink)
|
||||||
|
lcd_printPGM(PSTR(MSG_Z));
|
||||||
|
else {
|
||||||
|
if (!axis_homed[Z_AXIS])
|
||||||
|
lcd_printPGM(PSTR("?"));
|
||||||
|
else {
|
||||||
|
#if DISABLED(DISABLE_REDUCED_ACCURACY_WARNING)
|
||||||
|
if (!axis_known_position[Z_AXIS])
|
||||||
|
lcd_printPGM(PSTR(" "));
|
||||||
|
else
|
||||||
|
#endif
|
||||||
|
lcd_printPGM(PSTR(MSG_Z));
|
||||||
|
}
|
||||||
|
}
|
||||||
u8g.drawPixel(89, XYZ_BASELINE - 5);
|
u8g.drawPixel(89, XYZ_BASELINE - 5);
|
||||||
u8g.drawPixel(89, XYZ_BASELINE - 3);
|
u8g.drawPixel(89, XYZ_BASELINE - 3);
|
||||||
u8g.setPrintPos(91, XYZ_BASELINE);
|
u8g.setPrintPos(91, XYZ_BASELINE);
|
||||||
if (axis_known_position[Z_AXIS])
|
lcd_print(ftostr32sp(current_position[Z_AXIS]));
|
||||||
lcd_print(ftostr32sp(current_position[Z_AXIS]));
|
|
||||||
else
|
|
||||||
lcd_printPGM(PSTR("---.--"));
|
|
||||||
u8g.setColorIndex(1); // black on white
|
u8g.setColorIndex(1); // black on white
|
||||||
|
|
||||||
// Feedrate
|
// Feedrate
|
||||||
|
@ -411,13 +476,13 @@ static void lcd_implementation_status_screen() {
|
||||||
static void lcd_implementation_mark_as_selected(uint8_t row, bool isSelected) {
|
static void lcd_implementation_mark_as_selected(uint8_t row, bool isSelected) {
|
||||||
if (isSelected) {
|
if (isSelected) {
|
||||||
u8g.setColorIndex(1); // black on white
|
u8g.setColorIndex(1); // black on white
|
||||||
u8g.drawBox(0, row * DOG_CHAR_HEIGHT + 3 - TALL_FONT_CORRECTION, LCD_PIXEL_WIDTH, DOG_CHAR_HEIGHT);
|
u8g.drawBox(0, row * (DOG_CHAR_HEIGHT) + 3 - (TALL_FONT_CORRECTION), LCD_PIXEL_WIDTH, DOG_CHAR_HEIGHT);
|
||||||
u8g.setColorIndex(0); // following text must be white on black
|
u8g.setColorIndex(0); // following text must be white on black
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
u8g.setColorIndex(1); // unmarked text is black on white
|
u8g.setColorIndex(1); // unmarked text is black on white
|
||||||
}
|
}
|
||||||
u8g.setPrintPos(START_ROW * DOG_CHAR_WIDTH, (row + 1) * DOG_CHAR_HEIGHT);
|
u8g.setPrintPos((START_ROW) * (DOG_CHAR_WIDTH), (row + 1) * (DOG_CHAR_HEIGHT));
|
||||||
}
|
}
|
||||||
|
|
||||||
static void lcd_implementation_drawmenu_generic(bool isSelected, uint8_t row, const char* pstr, char pre_char, char post_char) {
|
static void lcd_implementation_drawmenu_generic(bool isSelected, uint8_t row, const char* pstr, char pre_char, char post_char) {
|
||||||
|
@ -431,7 +496,7 @@ static void lcd_implementation_drawmenu_generic(bool isSelected, uint8_t row, co
|
||||||
pstr++;
|
pstr++;
|
||||||
}
|
}
|
||||||
while (n--) lcd_print(' ');
|
while (n--) lcd_print(' ');
|
||||||
u8g.setPrintPos(LCD_PIXEL_WIDTH - DOG_CHAR_WIDTH, (row + 1) * DOG_CHAR_HEIGHT);
|
u8g.setPrintPos(LCD_PIXEL_WIDTH - (DOG_CHAR_WIDTH), (row + 1) * (DOG_CHAR_HEIGHT));
|
||||||
lcd_print(post_char);
|
lcd_print(post_char);
|
||||||
lcd_print(' ');
|
lcd_print(' ');
|
||||||
}
|
}
|
||||||
|
@ -449,7 +514,7 @@ static void _drawmenu_setting_edit_generic(bool isSelected, uint8_t row, const c
|
||||||
}
|
}
|
||||||
lcd_print(':');
|
lcd_print(':');
|
||||||
while (n--) lcd_print(' ');
|
while (n--) lcd_print(' ');
|
||||||
u8g.setPrintPos(LCD_PIXEL_WIDTH - DOG_CHAR_WIDTH * vallen, (row + 1) * DOG_CHAR_HEIGHT);
|
u8g.setPrintPos(LCD_PIXEL_WIDTH - (DOG_CHAR_WIDTH) * vallen, (row + 1) * (DOG_CHAR_HEIGHT));
|
||||||
if (pgm) lcd_printPGM(data); else lcd_print((char*)data);
|
if (pgm) lcd_printPGM(data); else lcd_print((char*)data);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -477,7 +542,7 @@ static void _drawmenu_setting_edit_generic(bool isSelected, uint8_t row, const c
|
||||||
#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)))
|
#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)))
|
||||||
#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))
|
#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))
|
||||||
|
|
||||||
void lcd_implementation_drawedit(const char* pstr, char* value) {
|
void lcd_implementation_drawedit(const char* pstr, const char* value) {
|
||||||
uint8_t rows = 1;
|
uint8_t rows = 1;
|
||||||
uint8_t lcd_width = LCD_WIDTH, char_width = DOG_CHAR_WIDTH;
|
uint8_t lcd_width = LCD_WIDTH, char_width = DOG_CHAR_WIDTH;
|
||||||
uint8_t vallen = lcd_strlen(value);
|
uint8_t vallen = lcd_strlen(value);
|
||||||
|
@ -496,14 +561,16 @@ void lcd_implementation_drawedit(const char* pstr, char* value) {
|
||||||
|
|
||||||
if (lcd_strlen_P(pstr) > LCD_WIDTH - 2 - vallen) rows = 2;
|
if (lcd_strlen_P(pstr) > LCD_WIDTH - 2 - vallen) rows = 2;
|
||||||
|
|
||||||
const float kHalfChar = DOG_CHAR_HEIGHT_EDIT / 2;
|
const float kHalfChar = (DOG_CHAR_HEIGHT_EDIT) / 2;
|
||||||
float rowHeight = u8g.getHeight() / (rows + 1); // 1/(rows+1) = 1/2 or 1/3
|
float rowHeight = u8g.getHeight() / (rows + 1); // 1/(rows+1) = 1/2 or 1/3
|
||||||
|
|
||||||
u8g.setPrintPos(0, rowHeight + kHalfChar);
|
u8g.setPrintPos(0, rowHeight + kHalfChar);
|
||||||
lcd_printPGM(pstr);
|
lcd_printPGM(pstr);
|
||||||
lcd_print(':');
|
if (value != NULL) {
|
||||||
u8g.setPrintPos((lcd_width - 1 - vallen) * char_width, rows * rowHeight + kHalfChar);
|
lcd_print(':');
|
||||||
lcd_print(value);
|
u8g.setPrintPos((lcd_width - 1 - vallen) * char_width, rows * rowHeight + kHalfChar);
|
||||||
|
lcd_print(value);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
@ -532,7 +599,7 @@ void lcd_implementation_drawedit(const char* pstr, char* value) {
|
||||||
|
|
||||||
#endif //SDSUPPORT
|
#endif //SDSUPPORT
|
||||||
|
|
||||||
#define lcd_implementation_drawmenu_back(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0])
|
#define lcd_implementation_drawmenu_back(sel, row, pstr) lcd_implementation_drawmenu_generic(sel, row, pstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0])
|
||||||
#define lcd_implementation_drawmenu_submenu(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', LCD_STR_ARROW_RIGHT[0])
|
#define lcd_implementation_drawmenu_submenu(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', LCD_STR_ARROW_RIGHT[0])
|
||||||
#define lcd_implementation_drawmenu_gcode(sel, row, pstr, gcode) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ')
|
#define lcd_implementation_drawmenu_gcode(sel, row, pstr, gcode) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ')
|
||||||
#define lcd_implementation_drawmenu_function(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ')
|
#define lcd_implementation_drawmenu_function(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ')
|
||||||
|
|
|
@ -1,3 +1,40 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -7,8 +44,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -16,11 +55,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -110,6 +145,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -129,6 +165,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -144,7 +181,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 1
|
#define TEMP_SENSOR_0 1
|
||||||
#define TEMP_SENSOR_1 0
|
#define TEMP_SENSOR_1 0
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
|
@ -178,14 +215,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define HEATER_3_MAXTEMP 275
|
#define HEATER_3_MAXTEMP 275
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
|
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
|
||||||
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
|
//#define BED_WATTS (12.0*12.0/1.1) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -197,6 +229,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
|
@ -236,10 +269,10 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
|
|
||||||
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
||||||
|
|
||||||
// Felix Foil Heater
|
// Felix Foil Heater
|
||||||
|
@ -266,16 +299,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -296,8 +328,22 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
#define USE_XMIN_PLUG
|
||||||
|
#define USE_YMIN_PLUG
|
||||||
|
#define USE_ZMIN_PLUG
|
||||||
|
//#define USE_XMAX_PLUG
|
||||||
|
//#define USE_YMAX_PLUG
|
||||||
|
//#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -320,13 +366,53 @@ const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
#define DISABLE_MAX_ENDSTOPS
|
|
||||||
//#define DISABLE_MIN_ENDSTOPS
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -336,11 +422,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z false
|
#define DISABLE_Z false
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -363,6 +451,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define INVERT_E3_DIR false
|
#define INVERT_E3_DIR false
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
@ -398,24 +488,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
|
||||||
#define MESH_MIN_Y 10
|
#define MESH_MIN_Y 10
|
||||||
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
|
#define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -426,7 +518,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
//#define DEBUG_LEVELING_FEATURE
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
//#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
//#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
|
@ -438,7 +530,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -452,7 +544,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define FRONT_PROBE_BED_POSITION 20
|
#define FRONT_PROBE_BED_POSITION 20
|
||||||
#define BACK_PROBE_BED_POSITION 180
|
#define BACK_PROBE_BED_POSITION 180
|
||||||
|
|
||||||
#define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
|
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
|
||||||
|
|
||||||
// Set the number of grid points per dimension.
|
// Set the number of grid points per dimension.
|
||||||
// You probably don't need more than 3 (squared=9).
|
// You probably don't need more than 3 (squared=9).
|
||||||
|
@ -460,25 +552,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X 15
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y 180
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X 15
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y 20
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X 170
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
|
@ -486,16 +590,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
||||||
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
//#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
|
@ -509,37 +626,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
|
||||||
|
@ -571,10 +657,10 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// 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.
|
// 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.
|
||||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {76.190476, 76.190476, 1600, 164}
|
#define DEFAULT_AXIS_STEPS_PER_UNIT {76.190476, 76.190476, 1600, 164}
|
||||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec)
|
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec)
|
||||||
#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.
|
#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.
|
||||||
|
|
||||||
#define DEFAULT_ACCELERATION 1750 //1500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
#define DEFAULT_ACCELERATION 1750 //1500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
||||||
#define DEFAULT_RETRACT_ACCELERATION 5000 // X, Y, Z and E max acceleration in mm/s^2 for r retracts
|
#define DEFAULT_RETRACT_ACCELERATION 5000 // E acceleration in mm/s^2 for retracts
|
||||||
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
|
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
|
||||||
|
|
||||||
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
|
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
|
||||||
|
@ -614,6 +700,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -634,13 +728,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
@ -648,12 +742,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
//#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)
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
|
||||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
||||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
|
@ -670,13 +764,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -691,7 +785,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
@ -714,6 +808,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -727,7 +823,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
// SSD1306 OLED generic display support
|
// SSD1306 OLED generic display support
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define U8GLIB_SSD1306
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
|
@ -739,7 +835,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
#define FAST_PWM_FAN
|
#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
@ -819,21 +915,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#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
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
|
|
||||||
//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.
|
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
|
@ -1,3 +1,40 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -7,8 +44,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -16,11 +55,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -61,6 +96,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define SERIAL_PORT 0
|
#define SERIAL_PORT 0
|
||||||
|
|
||||||
// This determines the communication speed of the printer
|
// This determines the communication speed of the printer
|
||||||
|
// :[2400,9600,19200,38400,57600,115200,250000]
|
||||||
#define BAUDRATE 250000
|
#define BAUDRATE 250000
|
||||||
|
|
||||||
// Enable the Bluetooth serial interface on AT90USB devices
|
// Enable the Bluetooth serial interface on AT90USB devices
|
||||||
|
@ -81,17 +117,27 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
||||||
|
|
||||||
// This defines the number of extruders
|
// This defines the number of extruders
|
||||||
|
// :[1,2,3,4]
|
||||||
#define EXTRUDERS 2
|
#define EXTRUDERS 2
|
||||||
|
|
||||||
|
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
|
||||||
|
// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
|
||||||
|
// For the other hotends it is their distance from the extruder 0 hotend.
|
||||||
|
//#define EXTRUDER_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
|
||||||
|
//#define EXTRUDER_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
|
||||||
|
|
||||||
//// The following define selects which power supply you have. Please choose the one that matches your setup
|
//// The following define selects which power supply you have. Please choose the one that matches your setup
|
||||||
// 1 = ATX
|
// 1 = ATX
|
||||||
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
|
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
|
||||||
|
// :{1:'ATX',2:'X-Box 360'}
|
||||||
|
|
||||||
#define POWER_SUPPLY 1
|
#define POWER_SUPPLY 1
|
||||||
|
|
||||||
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
|
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
|
||||||
#define PS_DEFAULT_OFF
|
#define PS_DEFAULT_OFF
|
||||||
|
|
||||||
|
// @section temperature
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Thermal Settings ============================
|
//============================= Thermal Settings ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -99,6 +145,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -118,6 +165,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -133,7 +181,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 1
|
#define TEMP_SENSOR_0 1
|
||||||
#define TEMP_SENSOR_1 1
|
#define TEMP_SENSOR_1 1
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
|
@ -167,14 +215,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define HEATER_3_MAXTEMP 275
|
#define HEATER_3_MAXTEMP 275
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
|
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
|
||||||
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
|
//#define BED_WATTS (12.0*12.0/1.1) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -186,6 +229,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
|
@ -228,14 +272,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
// Felix Foil Heater
|
// Felix Foil Heater
|
||||||
#define DEFAULT_bedKp 103.37
|
#define DEFAULT_bedKp 103.37
|
||||||
#define DEFAULT_bedKi 2.79
|
#define DEFAULT_bedKi 2.79
|
||||||
#define DEFAULT_bedKd 956.94
|
#define DEFAULT_bedKd 956.94
|
||||||
|
|
||||||
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
||||||
#endif // PIDTEMPBED
|
#endif // PIDTEMPBED
|
||||||
|
|
||||||
|
// @section extruder
|
||||||
|
|
||||||
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
|
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
|
||||||
//can be software-disabled for whatever purposes by
|
//can be software-disabled for whatever purposes by
|
||||||
|
@ -251,16 +296,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -281,8 +325,22 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
#define USE_XMIN_PLUG
|
||||||
|
#define USE_YMIN_PLUG
|
||||||
|
#define USE_ZMIN_PLUG
|
||||||
|
//#define USE_XMAX_PLUG
|
||||||
|
//#define USE_YMAX_PLUG
|
||||||
|
//#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -305,40 +363,97 @@ const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
#define DISABLE_MAX_ENDSTOPS
|
|
||||||
//#define DISABLE_MIN_ENDSTOPS
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
// :{0:'Low',1:'High'}
|
||||||
#define X_ENABLE_ON 0
|
#define X_ENABLE_ON 0
|
||||||
#define Y_ENABLE_ON 0
|
#define Y_ENABLE_ON 0
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z false
|
#define DISABLE_Z false
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
|
// @section extruder
|
||||||
|
|
||||||
#define DISABLE_E false // For all extruders
|
#define DISABLE_E false // For all extruders
|
||||||
#define DISABLE_INACTIVE_EXTRUDER true //disable only inactive extruders and keep active extruder enabled
|
#define DISABLE_INACTIVE_EXTRUDER true //disable only inactive extruders and keep active extruder enabled
|
||||||
|
|
||||||
|
// @section machine
|
||||||
|
|
||||||
// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
|
// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
|
||||||
#define INVERT_X_DIR true
|
#define INVERT_X_DIR true
|
||||||
#define INVERT_Y_DIR true
|
#define INVERT_Y_DIR true
|
||||||
#define INVERT_Z_DIR true
|
#define INVERT_Z_DIR true
|
||||||
|
|
||||||
|
// @section extruder
|
||||||
|
|
||||||
|
// For direct drive extruder v9 set to true, for geared extruder set to false.
|
||||||
#define INVERT_E0_DIR false
|
#define INVERT_E0_DIR false
|
||||||
#define INVERT_E1_DIR true
|
#define INVERT_E1_DIR true
|
||||||
#define INVERT_E2_DIR false
|
#define INVERT_E2_DIR false
|
||||||
#define INVERT_E3_DIR false
|
#define INVERT_E3_DIR false
|
||||||
|
|
||||||
|
// @section homing
|
||||||
|
//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
// :[-1,1]
|
||||||
#define X_HOME_DIR -1
|
#define X_HOME_DIR -1
|
||||||
#define Y_HOME_DIR -1
|
#define Y_HOME_DIR -1
|
||||||
#define Z_HOME_DIR -1
|
#define Z_HOME_DIR -1
|
||||||
|
@ -346,6 +461,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
|
#define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
|
||||||
#define max_software_endstops true // If true, axis won't move to coordinates greater than the defined lengths below.
|
#define max_software_endstops true // If true, axis won't move to coordinates greater than the defined lengths below.
|
||||||
|
|
||||||
|
// @section machine
|
||||||
|
|
||||||
// Travel limits after homing (units are in mm)
|
// Travel limits after homing (units are in mm)
|
||||||
#define X_MIN_POS 0
|
#define X_MIN_POS 0
|
||||||
#define Y_MIN_POS 0
|
#define Y_MIN_POS 0
|
||||||
|
@ -368,24 +485,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
|
||||||
#define MESH_MIN_Y 10
|
#define MESH_MIN_Y 10
|
||||||
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
|
#define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -394,10 +513,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section bedlevel
|
// @section bedlevel
|
||||||
|
|
||||||
|
|
||||||
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
//#define DEBUG_LEVELING_FEATURE
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
//#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
//#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
|
@ -409,7 +527,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -423,7 +541,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define FRONT_PROBE_BED_POSITION 20
|
#define FRONT_PROBE_BED_POSITION 20
|
||||||
#define BACK_PROBE_BED_POSITION 180
|
#define BACK_PROBE_BED_POSITION 180
|
||||||
|
|
||||||
#define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
|
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
|
||||||
|
|
||||||
// Set the number of grid points per dimension.
|
// Set the number of grid points per dimension.
|
||||||
// You probably don't need more than 3 (squared=9).
|
// You probably don't need more than 3 (squared=9).
|
||||||
|
@ -431,25 +549,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X 15
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y 180
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X 15
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y 20
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X 170
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
|
@ -457,16 +587,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
||||||
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
//#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
|
@ -480,40 +623,11 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
|
||||||
|
// @section homing
|
||||||
|
|
||||||
// The position of the homing switches
|
// The position of the homing switches
|
||||||
//#define MANUAL_HOME_POSITIONS // If defined, MANUAL_*_HOME_POS below will be used
|
//#define MANUAL_HOME_POSITIONS // If defined, MANUAL_*_HOME_POS below will be used
|
||||||
//#define BED_CENTER_AT_0_0 // If defined, the center of the bed is at (X=0, Y=0)
|
//#define BED_CENTER_AT_0_0 // If defined, the center of the bed is at (X=0, Y=0)
|
||||||
|
@ -527,6 +641,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define MANUAL_Z_HOME_POS 402 // For delta: Distance between nozzle and print surface after homing.
|
//#define MANUAL_Z_HOME_POS 402 // For delta: Distance between nozzle and print surface after homing.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// @section movement
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* MOVEMENT SETTINGS
|
* MOVEMENT SETTINGS
|
||||||
*/
|
*/
|
||||||
|
@ -538,18 +654,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// 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.
|
// 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.
|
||||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {76.190476, 76.190476, 1600, 164}
|
#define DEFAULT_AXIS_STEPS_PER_UNIT {76.190476, 76.190476, 1600, 164}
|
||||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec)
|
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec)
|
||||||
#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.
|
#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.
|
||||||
|
|
||||||
#define DEFAULT_ACCELERATION 1750 //1500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
#define DEFAULT_ACCELERATION 1750 //1500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
||||||
#define DEFAULT_RETRACT_ACCELERATION 5000 // X, Y, Z and E max acceleration in mm/s^2 for r retracts
|
#define DEFAULT_RETRACT_ACCELERATION 5000 // E acceleration in mm/s^2 for retracts
|
||||||
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
|
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
|
||||||
|
|
||||||
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
|
|
||||||
// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
|
|
||||||
// For the other hotends it is their distance from the extruder 0 hotend.
|
|
||||||
//#define EXTRUDER_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
|
|
||||||
//#define EXTRUDER_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
|
|
||||||
|
|
||||||
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
|
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
|
||||||
#define DEFAULT_XYJERK 10 // (mm/sec)
|
#define DEFAULT_XYJERK 10 // (mm/sec)
|
||||||
#define DEFAULT_ZJERK 0.3 //0.4 // (mm/sec)
|
#define DEFAULT_ZJERK 0.3 //0.4 // (mm/sec)
|
||||||
|
@ -560,6 +670,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
|
|
||||||
|
// @section more
|
||||||
|
|
||||||
// Custom M code points
|
// Custom M code points
|
||||||
#define CUSTOM_M_CODES
|
#define CUSTOM_M_CODES
|
||||||
#if ENABLED(CUSTOM_M_CODES)
|
#if ENABLED(CUSTOM_M_CODES)
|
||||||
|
@ -570,6 +682,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// @section extras
|
||||||
|
|
||||||
// EEPROM
|
// EEPROM
|
||||||
// The microcontroller can store settings in the EEPROM, e.g. max velocity...
|
// The microcontroller can store settings in the EEPROM, e.g. max velocity...
|
||||||
|
@ -581,9 +694,17 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#if ENABLED(EEPROM_SETTINGS)
|
#if ENABLED(EEPROM_SETTINGS)
|
||||||
// To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
|
// To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
|
||||||
#define EEPROM_CHITCHAT // please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -601,15 +722,16 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
|
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
|
||||||
|
|
||||||
//==============================LCD and SD support=============================
|
//==============================LCD and SD support=============================
|
||||||
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
@ -617,19 +739,18 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
//#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)
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
|
||||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
||||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
|
||||||
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
|
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
|
||||||
|
|
||||||
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
|
||||||
// http://reprap.org/wiki/PanelOne
|
// http://reprap.org/wiki/PanelOne
|
||||||
//#define PANEL_ONE
|
//#define PANEL_ONE
|
||||||
|
@ -640,13 +761,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -661,7 +782,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
@ -684,6 +805,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -696,14 +819,20 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
|
// Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
|
// SSD1306 OLED generic display support
|
||||||
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
// ---------------------
|
// ---------------------
|
||||||
// 2 wire Non-latching LCD SR from:
|
// 2 wire Non-latching LCD SR from:
|
||||||
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
|
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
|
||||||
|
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
|
||||||
//#define SAV_3DLCD
|
//#define SAV_3DLCD
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// @section extras
|
||||||
|
|
||||||
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
#define FAST_PWM_FAN
|
#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
@ -726,7 +855,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// Data from: http://www.doc-diy.net/photo/rc-1_hacked/
|
// Data from: http://www.doc-diy.net/photo/rc-1_hacked/
|
||||||
//#define PHOTOGRAPH_PIN 23
|
//#define PHOTOGRAPH_PIN 23
|
||||||
|
|
||||||
// SF send wrong arc g-codes when using Arc Point as fillet procedure
|
// SkeinForge sends the wrong arc g-codes when using Arc Point as fillet procedure
|
||||||
//#define SF_ARC_FIX
|
//#define SF_ARC_FIX
|
||||||
|
|
||||||
// Support for the BariCUDA Paste Extruder.
|
// Support for the BariCUDA Paste Extruder.
|
||||||
|
@ -783,21 +912,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#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
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
|
|
||||||
//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.
|
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
|
@ -1,3 +1,35 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration_adv.h
|
||||||
|
*
|
||||||
|
* Advanced settings.
|
||||||
|
* Only change these if you know exactly what you're doing.
|
||||||
|
* Some of these settings can damage your printer if improperly set!
|
||||||
|
*
|
||||||
|
* Basic settings can be found in Configuration.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
|
|
||||||
|
@ -9,13 +41,26 @@
|
||||||
//=============================Thermal Settings ============================
|
//=============================Thermal Settings ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
#if DISABLED(PIDTEMPBED)
|
||||||
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||||
|
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||||
|
#define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection parameters
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
|
*
|
||||||
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
|
*
|
||||||
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
|
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
||||||
|
* the firmware will halt the machine as a safety precaution.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
|
||||||
*/
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
||||||
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
||||||
|
@ -26,26 +71,24 @@
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* but only if the current temperature is far enough below the target for a reliable test.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
|
||||||
|
* WATCH_TEMP_INCREASE should not be below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 16 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 4 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Thermal Protection parameters for the bed
|
||||||
|
* are like the above for the hotends.
|
||||||
|
* WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
|
||||||
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_BED)
|
#if ENABLED(THERMAL_PROTECTION_BED)
|
||||||
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
|
||||||
* Automatic Temperature:
|
|
||||||
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
|
||||||
* The maximum buffered steps/sec of the extruder motor is called "se".
|
|
||||||
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
|
||||||
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
|
||||||
* mintemp and maxtemp. Turn this off by excuting M109 without F*
|
|
||||||
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
|
||||||
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
|
||||||
*/
|
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||||
|
@ -56,14 +99,16 @@
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
|
* Automatic Temperature:
|
||||||
//The maximum buffered steps/sec of the extruder motor are called "se".
|
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
||||||
//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
|
* The maximum buffered steps/sec of the extruder motor is called "se".
|
||||||
// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
|
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
||||||
// you exit the value by any M109 without F*
|
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
||||||
// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
|
* mintemp and maxtemp. Turn this off by executing M109 without F*
|
||||||
// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
||||||
|
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
||||||
|
*/
|
||||||
#define AUTOTEMP
|
#define AUTOTEMP
|
||||||
#if ENABLED(AUTOTEMP)
|
#if ENABLED(AUTOTEMP)
|
||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
|
@ -156,9 +201,7 @@
|
||||||
//#define Z_DUAL_ENDSTOPS
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_MAX_PIN 36 //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36)
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
const bool Z2_MAX_ENDSTOP_INVERTING = false;
|
|
||||||
#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.
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
#endif // Z_DUAL_STEPPER_DRIVERS
|
||||||
|
@ -240,7 +283,13 @@
|
||||||
#define INVERT_E_STEP_PIN false
|
#define INVERT_E_STEP_PIN false
|
||||||
|
|
||||||
// Default stepper release if idle. Set to 0 to deactivate.
|
// Default stepper release if idle. Set to 0 to deactivate.
|
||||||
|
// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
|
||||||
|
// Time can be set by M18 and M84.
|
||||||
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
||||||
|
#define DISABLE_INACTIVE_X true
|
||||||
|
#define DISABLE_INACTIVE_Y true
|
||||||
|
#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished.
|
||||||
|
#define DISABLE_INACTIVE_E true
|
||||||
|
|
||||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
||||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
||||||
|
@ -276,6 +325,9 @@
|
||||||
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
||||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||||
|
|
||||||
|
// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
|
||||||
|
//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
|
||||||
|
|
||||||
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
||||||
|
@ -349,17 +401,16 @@
|
||||||
//#define USE_SMALL_INFOFONT
|
//#define USE_SMALL_INFOFONT
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
|
|
||||||
// @section more
|
// @section more
|
||||||
|
|
||||||
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
||||||
//#define USE_WATCHDOG
|
#define USE_WATCHDOG
|
||||||
|
|
||||||
#if ENABLED(USE_WATCHDOG)
|
#if ENABLED(USE_WATCHDOG)
|
||||||
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
||||||
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
||||||
// 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.
|
// 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.
|
||||||
//#define WATCHDOG_RESET_MANUAL
|
//#define WATCHDOG_RESET_MANUAL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
@ -370,6 +421,7 @@
|
||||||
//#define BABYSTEPPING
|
//#define BABYSTEPPING
|
||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
||||||
|
//not implemented for deltabots!
|
||||||
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
||||||
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
||||||
#endif
|
#endif
|
||||||
|
@ -388,7 +440,6 @@
|
||||||
#if ENABLED(ADVANCE)
|
#if ENABLED(ADVANCE)
|
||||||
#define EXTRUDER_ADVANCE_K .0
|
#define EXTRUDER_ADVANCE_K .0
|
||||||
#define D_FILAMENT 2.85
|
#define D_FILAMENT 2.85
|
||||||
#define STEPS_MM_E 836
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
@ -397,7 +448,7 @@
|
||||||
#define MM_PER_ARC_SEGMENT 1
|
#define MM_PER_ARC_SEGMENT 1
|
||||||
#define N_ARC_CORRECTION 25
|
#define N_ARC_CORRECTION 25
|
||||||
|
|
||||||
const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
|
@ -462,12 +513,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
#define FILAMENTCHANGE_ZADD 10
|
#define FILAMENTCHANGE_ZADD 10
|
||||||
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||||
#define FILAMENTCHANGE_FINALRETRACT -100
|
#define FILAMENTCHANGE_FINALRETRACT -100
|
||||||
|
#define AUTO_FILAMENT_CHANGE //This extrude filament until you press the button on LCD
|
||||||
|
#define AUTO_FILAMENT_CHANGE_LENGTH 0.04 //Extrusion length on automatic extrusion loop
|
||||||
|
#define AUTO_FILAMENT_CHANGE_FEEDRATE 300 //Extrusion feedrate (mm/min) on automatic extrusion loop
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have TMC26X motor drivers.
|
* enable this section if you have TMC26X motor drivers.
|
||||||
* you need to import the TMC26XStepper library into the arduino IDE for this
|
* you need to import the TMC26XStepper library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section tmc
|
// @section tmc
|
||||||
|
@ -475,52 +529,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_TMCDRIVER
|
//#define HAVE_TMCDRIVER
|
||||||
#if ENABLED(HAVE_TMCDRIVER)
|
#if ENABLED(HAVE_TMCDRIVER)
|
||||||
|
|
||||||
//#define X_IS_TMC
|
//#define X_IS_TMC
|
||||||
#define X_MAX_CURRENT 1000 //in mA
|
#define X_MAX_CURRENT 1000 //in mA
|
||||||
#define X_SENSE_RESISTOR 91 //in mOhms
|
#define X_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define X2_IS_TMC
|
//#define X2_IS_TMC
|
||||||
#define X2_MAX_CURRENT 1000 //in mA
|
#define X2_MAX_CURRENT 1000 //in mA
|
||||||
#define X2_SENSE_RESISTOR 91 //in mOhms
|
#define X2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y_IS_TMC
|
//#define Y_IS_TMC
|
||||||
#define Y_MAX_CURRENT 1000 //in mA
|
#define Y_MAX_CURRENT 1000 //in mA
|
||||||
#define Y_SENSE_RESISTOR 91 //in mOhms
|
#define Y_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y2_IS_TMC
|
//#define Y2_IS_TMC
|
||||||
#define Y2_MAX_CURRENT 1000 //in mA
|
#define Y2_MAX_CURRENT 1000 //in mA
|
||||||
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z_IS_TMC
|
//#define Z_IS_TMC
|
||||||
#define Z_MAX_CURRENT 1000 //in mA
|
#define Z_MAX_CURRENT 1000 //in mA
|
||||||
#define Z_SENSE_RESISTOR 91 //in mOhms
|
#define Z_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z2_IS_TMC
|
//#define Z2_IS_TMC
|
||||||
#define Z2_MAX_CURRENT 1000 //in mA
|
#define Z2_MAX_CURRENT 1000 //in mA
|
||||||
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E0_IS_TMC
|
//#define E0_IS_TMC
|
||||||
#define E0_MAX_CURRENT 1000 //in mA
|
#define E0_MAX_CURRENT 1000 //in mA
|
||||||
#define E0_SENSE_RESISTOR 91 //in mOhms
|
#define E0_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E1_IS_TMC
|
//#define E1_IS_TMC
|
||||||
#define E1_MAX_CURRENT 1000 //in mA
|
#define E1_MAX_CURRENT 1000 //in mA
|
||||||
#define E1_SENSE_RESISTOR 91 //in mOhms
|
#define E1_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E2_IS_TMC
|
//#define E2_IS_TMC
|
||||||
#define E2_MAX_CURRENT 1000 //in mA
|
#define E2_MAX_CURRENT 1000 //in mA
|
||||||
#define E2_SENSE_RESISTOR 91 //in mOhms
|
#define E2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E3_IS_TMC
|
//#define E3_IS_TMC
|
||||||
#define E3_MAX_CURRENT 1000 //in mA
|
#define E3_MAX_CURRENT 1000 //in mA
|
||||||
#define E3_SENSE_RESISTOR 91 //in mOhms
|
#define E3_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
|
@ -529,7 +583,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have L6470 motor drivers.
|
* enable this section if you have L6470 motor drivers.
|
||||||
* you need to import the L6470 library into the arduino IDE for this
|
* you need to import the L6470 library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section l6470
|
// @section l6470
|
||||||
|
@ -537,63 +591,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_L6470DRIVER
|
//#define HAVE_L6470DRIVER
|
||||||
#if ENABLED(HAVE_L6470DRIVER)
|
#if ENABLED(HAVE_L6470DRIVER)
|
||||||
|
|
||||||
//#define X_IS_L6470
|
//#define X_IS_L6470
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define X2_IS_L6470
|
//#define X2_IS_L6470
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y_IS_L6470
|
//#define Y_IS_L6470
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y2_IS_L6470
|
//#define Y2_IS_L6470
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z_IS_L6470
|
//#define Z_IS_L6470
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z2_IS_L6470
|
//#define Z2_IS_L6470
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E0_IS_L6470
|
//#define E0_IS_L6470
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E1_IS_L6470
|
//#define E1_IS_L6470
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E2_IS_L6470
|
//#define E2_IS_L6470
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E3_IS_L6470
|
//#define E3_IS_L6470
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,40 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -7,8 +44,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -16,11 +55,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -70,7 +105,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// The following define selects which electronics board you have.
|
// The following define selects which electronics board you have.
|
||||||
// Please choose the name from boards.h that matches your setup
|
// Please choose the name from boards.h that matches your setup
|
||||||
#ifndef MOTHERBOARD
|
#ifndef MOTHERBOARD
|
||||||
#define MOTHERBOARD BOARD_RAMPS_13_EFB
|
#define MOTHERBOARD BOARD_RAMPS_14_EFB
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Optional custom name for your RepStrap or other custom machine
|
// Optional custom name for your RepStrap or other custom machine
|
||||||
|
@ -113,6 +148,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -132,6 +168,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -147,7 +184,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 1
|
#define TEMP_SENSOR_0 1
|
||||||
#define TEMP_SENSOR_1 0
|
#define TEMP_SENSOR_1 0
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
|
@ -181,14 +218,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define HEATER_3_MAXTEMP 260
|
#define HEATER_3_MAXTEMP 260
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
|
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
|
||||||
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
|
//#define BED_WATTS (12.0*12.0/1.1) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -200,6 +232,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
|
@ -239,19 +272,19 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
|
|
||||||
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||||
#define DEFAULT_bedKp 10.00
|
#define DEFAULT_bedKp 10.00
|
||||||
#define DEFAULT_bedKi .023
|
#define DEFAULT_bedKi .023
|
||||||
#define DEFAULT_bedKd 305.4
|
#define DEFAULT_bedKd 305.4
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from pidautotune
|
//from pidautotune
|
||||||
//#define DEFAULT_bedKp 97.1
|
//#define DEFAULT_bedKp 97.1
|
||||||
//#define DEFAULT_bedKi 1.41
|
//#define DEFAULT_bedKi 1.41
|
||||||
|
@ -276,16 +309,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -306,8 +338,22 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
#define USE_XMIN_PLUG
|
||||||
|
#define USE_YMIN_PLUG
|
||||||
|
#define USE_ZMIN_PLUG
|
||||||
|
//#define USE_XMAX_PLUG
|
||||||
|
//#define USE_YMAX_PLUG
|
||||||
|
//#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -330,13 +376,53 @@ const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
//#define DISABLE_MAX_ENDSTOPS
|
|
||||||
//#define DISABLE_MIN_ENDSTOPS
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -346,11 +432,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z false
|
#define DISABLE_Z false
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -373,6 +461,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define INVERT_E3_DIR false
|
#define INVERT_E3_DIR false
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
@ -408,24 +498,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
|
||||||
#define MESH_MIN_Y 10
|
#define MESH_MIN_Y 10
|
||||||
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
|
#define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -434,10 +526,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
// @section bedlevel
|
// @section bedlevel
|
||||||
|
|
||||||
|
|
||||||
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
//#define DEBUG_LEVELING_FEATURE
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
|
@ -449,7 +540,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -463,7 +554,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define FRONT_PROBE_BED_POSITION 20
|
#define FRONT_PROBE_BED_POSITION 20
|
||||||
#define BACK_PROBE_BED_POSITION 170
|
#define BACK_PROBE_BED_POSITION 170
|
||||||
|
|
||||||
#define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
|
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
|
||||||
|
|
||||||
// Set the number of grid points per dimension.
|
// Set the number of grid points per dimension.
|
||||||
// You probably don't need more than 3 (squared=9).
|
// You probably don't need more than 3 (squared=9).
|
||||||
|
@ -471,25 +562,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X 15
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y 180
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X 15
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y 20
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X 170
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
|
@ -497,16 +600,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
||||||
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
//#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
|
@ -520,37 +636,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
|
||||||
|
@ -624,6 +709,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -644,13 +737,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
@ -658,11 +751,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define ULTRA_LCD //general LCD support, also 16x2
|
#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
//#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)
|
||||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
||||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
|
@ -679,13 +773,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -700,7 +794,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
@ -717,12 +811,17 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// http://reprap.org/wiki/Mini_panel
|
// http://reprap.org/wiki/Mini_panel
|
||||||
//#define MINIPANEL
|
//#define MINIPANEL
|
||||||
|
|
||||||
|
// BQ SMART FULL GRAPHIC CONTROLLER
|
||||||
|
//#define BQ_LCD_SMART_CONTROLLER
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* I2C Panels
|
* I2C Panels
|
||||||
*/
|
*/
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -736,7 +835,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
// SSD1306 OLED generic display support
|
// SSD1306 OLED generic display support
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define U8GLIB_SSD1306
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
|
@ -748,7 +847,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
//#define FAST_PWM_FAN
|
//#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
@ -828,21 +927,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#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
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
|
|
||||||
//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.
|
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
|
@ -1,3 +1,35 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration_adv.h
|
||||||
|
*
|
||||||
|
* Advanced settings.
|
||||||
|
* Only change these if you know exactly what you're doing.
|
||||||
|
* Some of these settings can damage your printer if improperly set!
|
||||||
|
*
|
||||||
|
* Basic settings can be found in Configuration.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
|
|
||||||
|
@ -9,13 +41,26 @@
|
||||||
//=============================Thermal Settings ============================
|
//=============================Thermal Settings ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
#if DISABLED(PIDTEMPBED)
|
||||||
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||||
|
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||||
|
#define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection parameters
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
|
*
|
||||||
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
|
*
|
||||||
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
|
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
||||||
|
* the firmware will halt the machine as a safety precaution.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
|
||||||
*/
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
||||||
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
||||||
|
@ -26,26 +71,24 @@
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* but only if the current temperature is far enough below the target for a reliable test.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
|
||||||
|
* WATCH_TEMP_INCREASE should not be below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 16 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 4 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Thermal Protection parameters for the bed
|
||||||
|
* are like the above for the hotends.
|
||||||
|
* WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
|
||||||
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_BED)
|
#if ENABLED(THERMAL_PROTECTION_BED)
|
||||||
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
|
||||||
* Automatic Temperature:
|
|
||||||
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
|
||||||
* The maximum buffered steps/sec of the extruder motor is called "se".
|
|
||||||
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
|
||||||
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
|
||||||
* mintemp and maxtemp. Turn this off by excuting M109 without F*
|
|
||||||
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
|
||||||
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
|
||||||
*/
|
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||||
|
@ -56,14 +99,16 @@
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
|
* Automatic Temperature:
|
||||||
//The maximum buffered steps/sec of the extruder motor are called "se".
|
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
||||||
//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
|
* The maximum buffered steps/sec of the extruder motor is called "se".
|
||||||
// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
|
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
||||||
// you exit the value by any M109 without F*
|
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
||||||
// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
|
* mintemp and maxtemp. Turn this off by executing M109 without F*
|
||||||
// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
||||||
|
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
||||||
|
*/
|
||||||
#define AUTOTEMP
|
#define AUTOTEMP
|
||||||
#if ENABLED(AUTOTEMP)
|
#if ENABLED(AUTOTEMP)
|
||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
|
@ -156,9 +201,7 @@
|
||||||
//#define Z_DUAL_ENDSTOPS
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_MAX_PIN 36 //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36)
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
const bool Z2_MAX_ENDSTOP_INVERTING = false;
|
|
||||||
#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.
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
#endif // Z_DUAL_STEPPER_DRIVERS
|
||||||
|
@ -240,7 +283,13 @@
|
||||||
#define INVERT_E_STEP_PIN false
|
#define INVERT_E_STEP_PIN false
|
||||||
|
|
||||||
// Default stepper release if idle. Set to 0 to deactivate.
|
// Default stepper release if idle. Set to 0 to deactivate.
|
||||||
|
// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
|
||||||
|
// Time can be set by M18 and M84.
|
||||||
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
||||||
|
#define DISABLE_INACTIVE_X true
|
||||||
|
#define DISABLE_INACTIVE_Y true
|
||||||
|
#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished.
|
||||||
|
#define DISABLE_INACTIVE_E true
|
||||||
|
|
||||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
||||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
||||||
|
@ -276,6 +325,9 @@
|
||||||
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
||||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||||
|
|
||||||
|
// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
|
||||||
|
//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
|
||||||
|
|
||||||
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
||||||
|
@ -349,17 +401,16 @@
|
||||||
//#define USE_SMALL_INFOFONT
|
//#define USE_SMALL_INFOFONT
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
|
|
||||||
// @section more
|
// @section more
|
||||||
|
|
||||||
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
||||||
//#define USE_WATCHDOG
|
#define USE_WATCHDOG
|
||||||
|
|
||||||
#if ENABLED(USE_WATCHDOG)
|
#if ENABLED(USE_WATCHDOG)
|
||||||
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
||||||
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
||||||
// 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.
|
// 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.
|
||||||
//#define WATCHDOG_RESET_MANUAL
|
//#define WATCHDOG_RESET_MANUAL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
@ -370,6 +421,7 @@
|
||||||
//#define BABYSTEPPING
|
//#define BABYSTEPPING
|
||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
||||||
|
//not implemented for deltabots!
|
||||||
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
||||||
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
||||||
#endif
|
#endif
|
||||||
|
@ -388,7 +440,6 @@
|
||||||
#if ENABLED(ADVANCE)
|
#if ENABLED(ADVANCE)
|
||||||
#define EXTRUDER_ADVANCE_K .0
|
#define EXTRUDER_ADVANCE_K .0
|
||||||
#define D_FILAMENT 1.75
|
#define D_FILAMENT 1.75
|
||||||
#define STEPS_MM_E 100.47095761381482
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
@ -397,7 +448,7 @@
|
||||||
#define MM_PER_ARC_SEGMENT 1
|
#define MM_PER_ARC_SEGMENT 1
|
||||||
#define N_ARC_CORRECTION 25
|
#define N_ARC_CORRECTION 25
|
||||||
|
|
||||||
const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
|
@ -446,11 +497,11 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt
|
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt
|
||||||
#define RETRACT_LENGTH 3 //default retract length (positive mm)
|
#define RETRACT_LENGTH 3 //default retract length (positive mm)
|
||||||
#define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change
|
#define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change
|
||||||
#define RETRACT_FEEDRATE 80*60 //default feedrate for retracting (mm/s)
|
#define RETRACT_FEEDRATE 80 //default feedrate for retracting (mm/s)
|
||||||
#define RETRACT_ZLIFT 0 //default retract Z-lift
|
#define RETRACT_ZLIFT 0 //default retract Z-lift
|
||||||
#define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering)
|
#define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering)
|
||||||
//#define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change)
|
//#define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change)
|
||||||
#define RETRACT_RECOVER_FEEDRATE 8*60 //default feedrate for recovering from retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Add support for experimental filament exchange support M600; requires display
|
// Add support for experimental filament exchange support M600; requires display
|
||||||
|
@ -462,12 +513,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
#define FILAMENTCHANGE_ZADD 10
|
#define FILAMENTCHANGE_ZADD 10
|
||||||
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||||
#define FILAMENTCHANGE_FINALRETRACT -100
|
#define FILAMENTCHANGE_FINALRETRACT -100
|
||||||
|
#define AUTO_FILAMENT_CHANGE //This extrude filament until you press the button on LCD
|
||||||
|
#define AUTO_FILAMENT_CHANGE_LENGTH 0.04 //Extrusion length on automatic extrusion loop
|
||||||
|
#define AUTO_FILAMENT_CHANGE_FEEDRATE 300 //Extrusion feedrate (mm/min) on automatic extrusion loop
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have TMC26X motor drivers.
|
* enable this section if you have TMC26X motor drivers.
|
||||||
* you need to import the TMC26XStepper library into the arduino IDE for this
|
* you need to import the TMC26XStepper library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section tmc
|
// @section tmc
|
||||||
|
@ -475,52 +529,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_TMCDRIVER
|
//#define HAVE_TMCDRIVER
|
||||||
#if ENABLED(HAVE_TMCDRIVER)
|
#if ENABLED(HAVE_TMCDRIVER)
|
||||||
|
|
||||||
//#define X_IS_TMC
|
//#define X_IS_TMC
|
||||||
#define X_MAX_CURRENT 1000 //in mA
|
#define X_MAX_CURRENT 1000 //in mA
|
||||||
#define X_SENSE_RESISTOR 91 //in mOhms
|
#define X_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define X2_IS_TMC
|
//#define X2_IS_TMC
|
||||||
#define X2_MAX_CURRENT 1000 //in mA
|
#define X2_MAX_CURRENT 1000 //in mA
|
||||||
#define X2_SENSE_RESISTOR 91 //in mOhms
|
#define X2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y_IS_TMC
|
//#define Y_IS_TMC
|
||||||
#define Y_MAX_CURRENT 1000 //in mA
|
#define Y_MAX_CURRENT 1000 //in mA
|
||||||
#define Y_SENSE_RESISTOR 91 //in mOhms
|
#define Y_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y2_IS_TMC
|
//#define Y2_IS_TMC
|
||||||
#define Y2_MAX_CURRENT 1000 //in mA
|
#define Y2_MAX_CURRENT 1000 //in mA
|
||||||
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z_IS_TMC
|
//#define Z_IS_TMC
|
||||||
#define Z_MAX_CURRENT 1000 //in mA
|
#define Z_MAX_CURRENT 1000 //in mA
|
||||||
#define Z_SENSE_RESISTOR 91 //in mOhms
|
#define Z_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z2_IS_TMC
|
//#define Z2_IS_TMC
|
||||||
#define Z2_MAX_CURRENT 1000 //in mA
|
#define Z2_MAX_CURRENT 1000 //in mA
|
||||||
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E0_IS_TMC
|
//#define E0_IS_TMC
|
||||||
#define E0_MAX_CURRENT 1000 //in mA
|
#define E0_MAX_CURRENT 1000 //in mA
|
||||||
#define E0_SENSE_RESISTOR 91 //in mOhms
|
#define E0_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E1_IS_TMC
|
//#define E1_IS_TMC
|
||||||
#define E1_MAX_CURRENT 1000 //in mA
|
#define E1_MAX_CURRENT 1000 //in mA
|
||||||
#define E1_SENSE_RESISTOR 91 //in mOhms
|
#define E1_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E2_IS_TMC
|
//#define E2_IS_TMC
|
||||||
#define E2_MAX_CURRENT 1000 //in mA
|
#define E2_MAX_CURRENT 1000 //in mA
|
||||||
#define E2_SENSE_RESISTOR 91 //in mOhms
|
#define E2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E3_IS_TMC
|
//#define E3_IS_TMC
|
||||||
#define E3_MAX_CURRENT 1000 //in mA
|
#define E3_MAX_CURRENT 1000 //in mA
|
||||||
#define E3_SENSE_RESISTOR 91 //in mOhms
|
#define E3_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
|
@ -529,7 +583,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have L6470 motor drivers.
|
* enable this section if you have L6470 motor drivers.
|
||||||
* you need to import the L6470 library into the arduino IDE for this
|
* you need to import the L6470 library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section l6470
|
// @section l6470
|
||||||
|
@ -537,63 +591,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_L6470DRIVER
|
//#define HAVE_L6470DRIVER
|
||||||
#if ENABLED(HAVE_L6470DRIVER)
|
#if ENABLED(HAVE_L6470DRIVER)
|
||||||
|
|
||||||
//#define X_IS_L6470
|
//#define X_IS_L6470
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define X2_IS_L6470
|
//#define X2_IS_L6470
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y_IS_L6470
|
//#define Y_IS_L6470
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y2_IS_L6470
|
//#define Y2_IS_L6470
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z_IS_L6470
|
//#define Z_IS_L6470
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z2_IS_L6470
|
//#define Z2_IS_L6470
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E0_IS_L6470
|
//#define E0_IS_L6470
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E1_IS_L6470
|
//#define E1_IS_L6470
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E2_IS_L6470
|
//#define E2_IS_L6470
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E3_IS_L6470
|
//#define E3_IS_L6470
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,40 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -7,8 +44,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -16,11 +55,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -47,7 +82,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// User-specified version info of this build to display in [Pronterface, etc] terminal window during
|
// User-specified version info of this build to display in [Pronterface, etc] terminal window during
|
||||||
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
|
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
|
||||||
// build by the user have been successfully uploaded into firmware.
|
// build by the user have been successfully uploaded into firmware.
|
||||||
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
|
#define STRING_CONFIG_H_AUTHOR "@jbrazio" // Who made the changes.
|
||||||
#define SHOW_BOOTSCREEN
|
#define SHOW_BOOTSCREEN
|
||||||
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
|
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
|
||||||
//#define STRING_SPLASH_LINE2 STRING_DISTRIBUTION_DATE // will be shown during bootup in line 2
|
//#define STRING_SPLASH_LINE2 STRING_DISTRIBUTION_DATE // will be shown during bootup in line 2
|
||||||
|
@ -70,16 +105,16 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// The following define selects which electronics board you have.
|
// The following define selects which electronics board you have.
|
||||||
// Please choose the name from boards.h that matches your setup
|
// Please choose the name from boards.h that matches your setup
|
||||||
#ifndef MOTHERBOARD
|
#ifndef MOTHERBOARD
|
||||||
#define MOTHERBOARD BOARD_RAMPS_13_EFB
|
#define MOTHERBOARD BOARD_BQ_ZUM_MEGA_3D
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Optional custom name for your RepStrap or other custom machine
|
// Optional custom name for your RepStrap or other custom machine
|
||||||
// Displayed in the LCD "Ready" message
|
// Displayed in the LCD "Ready" message
|
||||||
//#define CUSTOM_MACHINE_NAME "3D Printer"
|
#define CUSTOM_MACHINE_NAME "BQ Hephestos 2"
|
||||||
|
|
||||||
// Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
|
// Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
|
||||||
// You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4)
|
// You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4)
|
||||||
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
#define MACHINE_UUID "8d083632-40c5-4649-85b8-43d9ae6c5d55" // BQ Hephestos 2 standard config
|
||||||
|
|
||||||
// This defines the number of extruders
|
// This defines the number of extruders
|
||||||
// :[1,2,3,4]
|
// :[1,2,3,4]
|
||||||
|
@ -110,6 +145,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -129,6 +165,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -144,8 +181,8 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 1
|
#define TEMP_SENSOR_0 70
|
||||||
#define TEMP_SENSOR_1 0
|
#define TEMP_SENSOR_1 0
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
#define TEMP_SENSOR_3 0
|
#define TEMP_SENSOR_3 0
|
||||||
|
@ -172,20 +209,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// When temperature exceeds max temp, your heater will be switched off.
|
// When temperature exceeds max temp, your heater will be switched off.
|
||||||
// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
|
// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
|
||||||
// You should use MINTEMP for thermistor short/failure protection.
|
// You should use MINTEMP for thermistor short/failure protection.
|
||||||
#define HEATER_0_MAXTEMP 275
|
#define HEATER_0_MAXTEMP 250
|
||||||
#define HEATER_1_MAXTEMP 275
|
#define HEATER_1_MAXTEMP 275
|
||||||
#define HEATER_2_MAXTEMP 275
|
#define HEATER_2_MAXTEMP 275
|
||||||
#define HEATER_3_MAXTEMP 275
|
#define HEATER_3_MAXTEMP 275
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
|
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
|
||||||
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
|
//#define BED_WATTS (12.0*12.0/1.1) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -197,31 +229,26 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
//#define PID_PARAMS_PER_EXTRUDER // Uses separate PID parameters for each extruder (useful for mismatched extruders)
|
//#define PID_PARAMS_PER_EXTRUDER // Uses separate PID parameters for each extruder (useful for mismatched extruders)
|
||||||
// Set/get with gcode: M301 E[extruder number, 0-2]
|
// Set/get with gcode: M301 E[extruder number, 0-2]
|
||||||
#define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
|
#define PID_FUNCTIONAL_RANGE 250 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
|
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
|
||||||
#define K1 0.95 //smoothing factor within the PID
|
#define K1 0.95 //smoothing factor within the PID
|
||||||
|
|
||||||
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
// Tuned PID values using M303
|
||||||
// Ultimaker
|
#define DEFAULT_Kp 19.18
|
||||||
#define DEFAULT_Kp 22.2
|
#define DEFAULT_Ki 1.36
|
||||||
#define DEFAULT_Ki 1.08
|
#define DEFAULT_Kd 67.42
|
||||||
#define DEFAULT_Kd 114
|
|
||||||
|
|
||||||
// MakerGear
|
// BQ firmware stock PID values
|
||||||
//#define DEFAULT_Kp 7.0
|
//#define DEFAULT_Kp 10.7
|
||||||
//#define DEFAULT_Ki 0.1
|
//#define DEFAULT_Ki 0.45
|
||||||
//#define DEFAULT_Kd 12
|
//#define DEFAULT_Kd 3
|
||||||
|
|
||||||
// Mendel Parts V9 on 12V
|
|
||||||
//#define DEFAULT_Kp 63.0
|
|
||||||
//#define DEFAULT_Ki 2.25
|
|
||||||
//#define DEFAULT_Kd 440
|
|
||||||
|
|
||||||
#endif // PIDTEMP
|
#endif // PIDTEMP
|
||||||
|
|
||||||
|
@ -247,19 +274,19 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
|
|
||||||
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||||
#define DEFAULT_bedKp 10.00
|
#define DEFAULT_bedKp 10.00
|
||||||
#define DEFAULT_bedKi .023
|
#define DEFAULT_bedKi .023
|
||||||
#define DEFAULT_bedKd 305.4
|
#define DEFAULT_bedKd 305.4
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from pidautotune
|
//from pidautotune
|
||||||
//#define DEFAULT_bedKp 97.1
|
//#define DEFAULT_bedKp 97.1
|
||||||
//#define DEFAULT_bedKi 1.41
|
//#define DEFAULT_bedKi 1.41
|
||||||
|
@ -284,16 +311,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -314,8 +340,22 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
#define USE_XMIN_PLUG
|
||||||
|
#define USE_YMIN_PLUG
|
||||||
|
#define USE_ZMIN_PLUG
|
||||||
|
//#define USE_XMAX_PLUG
|
||||||
|
//#define USE_YMAX_PLUG
|
||||||
|
//#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -331,20 +371,60 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
|
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
|
||||||
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool X_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Y_MIN_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
const bool X_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
//#define DISABLE_MAX_ENDSTOPS
|
|
||||||
//#define DISABLE_MIN_ENDSTOPS
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -354,11 +434,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z false
|
#define DISABLE_Z false
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -368,19 +450,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// @section machine
|
// @section machine
|
||||||
|
|
||||||
// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
|
// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
|
||||||
#define INVERT_X_DIR false
|
#define INVERT_X_DIR true
|
||||||
#define INVERT_Y_DIR true
|
#define INVERT_Y_DIR true
|
||||||
#define INVERT_Z_DIR false
|
#define INVERT_Z_DIR true
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
// For direct drive extruder v9 set to true, for geared extruder set to false.
|
// For direct drive extruder v9 set to true, for geared extruder set to false.
|
||||||
#define INVERT_E0_DIR false
|
#define INVERT_E0_DIR true
|
||||||
#define INVERT_E1_DIR false
|
#define INVERT_E1_DIR false
|
||||||
#define INVERT_E2_DIR false
|
#define INVERT_E2_DIR false
|
||||||
#define INVERT_E3_DIR false
|
#define INVERT_E3_DIR false
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
#define MIN_Z_HEIGHT_FOR_HOMING 5 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
@ -389,8 +473,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Y_HOME_DIR -1
|
#define Y_HOME_DIR -1
|
||||||
#define Z_HOME_DIR -1
|
#define Z_HOME_DIR -1
|
||||||
|
|
||||||
#define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
|
#define min_software_endstops false // If true, axis won't move to coordinates less than HOME_POS.
|
||||||
#define max_software_endstops true // If true, axis won't move to coordinates greater than the defined lengths below.
|
#define max_software_endstops false // If true, axis won't move to coordinates greater than the defined lengths below.
|
||||||
|
|
||||||
// @section machine
|
// @section machine
|
||||||
|
|
||||||
|
@ -398,9 +482,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define X_MIN_POS 0
|
#define X_MIN_POS 0
|
||||||
#define Y_MIN_POS 0
|
#define Y_MIN_POS 0
|
||||||
#define Z_MIN_POS 0
|
#define Z_MIN_POS 0
|
||||||
#define X_MAX_POS 200
|
#define X_MAX_POS 210
|
||||||
#define Y_MAX_POS 200
|
#define Y_MAX_POS 297
|
||||||
#define Z_MAX_POS 200
|
#define Z_MAX_POS 210
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//========================= Filament Runout Sensor ==========================
|
//========================= Filament Runout Sensor ==========================
|
||||||
|
@ -416,16 +500,11 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
||||||
|
@ -434,6 +513,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -442,9 +528,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section bedlevel
|
// @section bedlevel
|
||||||
|
|
||||||
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
//#define DEBUG_LEVELING_FEATURE
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
|
@ -456,7 +542,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -465,12 +551,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_GRID)
|
#if ENABLED(AUTO_BED_LEVELING_GRID)
|
||||||
|
|
||||||
#define LEFT_PROBE_BED_POSITION 15
|
#define LEFT_PROBE_BED_POSITION X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
#define RIGHT_PROBE_BED_POSITION 170
|
#define RIGHT_PROBE_BED_POSITION X_MAX_POS - X_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
#define FRONT_PROBE_BED_POSITION 20
|
#define FRONT_PROBE_BED_POSITION Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
#define BACK_PROBE_BED_POSITION 170
|
#define BACK_PROBE_BED_POSITION Y_MAX_POS - Y_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
|
||||||
#define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
|
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
|
||||||
|
|
||||||
// Set the number of grid points per dimension.
|
// Set the number of grid points per dimension.
|
||||||
// You probably don't need more than 3 (squared=9).
|
// You probably don't need more than 3 (squared=9).
|
||||||
|
@ -478,42 +564,67 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X X_MAX_POS - X_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X ((X_MIN_POS + X_MAX_POS) / 2)
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y Y_MAX_POS - Y_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER 34 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER 15 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER 0 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
#define Z_RAISE_BEFORE_PROBING 15 // How much the Z axis will be raised before traveling to the first probing point.
|
#define Z_RAISE_BEFORE_PROBING 5 // How much the Z axis will be raised before traveling to the first probing point.
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
#define Z_RAISE_BETWEEN_PROBINGS 2 // How much the Z axis will be raised when traveling from between next probing points.
|
||||||
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 5 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
|
@ -527,37 +638,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
|
||||||
|
@ -582,22 +662,22 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
* MOVEMENT SETTINGS
|
* MOVEMENT SETTINGS
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define HOMING_FEEDRATE {50*60, 50*60, 4*60, 0} // set the homing speeds (mm/min)
|
#define HOMING_FEEDRATE {150*60, 150*60, 3.3*60, 0} // set the homing speeds (mm/min)
|
||||||
|
|
||||||
// default settings
|
// default settings
|
||||||
|
|
||||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {80,80,4000,500} // default steps per unit for Ultimaker
|
#define DEFAULT_AXIS_STEPS_PER_UNIT {160, 160, 8000, 204.146} // default steps per unit for Ultimaker
|
||||||
#define DEFAULT_MAX_FEEDRATE {300, 300, 5, 25} // (mm/sec)
|
#define DEFAULT_MAX_FEEDRATE {200, 200, 3.3, 200} // (mm/sec)
|
||||||
#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.
|
#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.
|
||||||
|
|
||||||
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
|
#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
|
||||||
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
|
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
|
||||||
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
|
#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
|
||||||
|
|
||||||
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
|
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
|
||||||
#define DEFAULT_XYJERK 20.0 // (mm/sec)
|
#define DEFAULT_XYJERK 15.0 // (mm/sec)
|
||||||
#define DEFAULT_ZJERK 0.4 // (mm/sec)
|
#define DEFAULT_ZJERK 0.4 // (mm/sec)
|
||||||
#define DEFAULT_EJERK 5.0 // (mm/sec)
|
#define DEFAULT_EJERK 2.0 // (mm/sec)
|
||||||
|
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
|
@ -611,8 +691,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#if ENABLED(CUSTOM_M_CODES)
|
#if ENABLED(CUSTOM_M_CODES)
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
#define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
|
#define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
|
||||||
#define Z_PROBE_OFFSET_RANGE_MIN -20
|
#define Z_PROBE_OFFSET_RANGE_MIN -5
|
||||||
#define Z_PROBE_OFFSET_RANGE_MAX 20
|
#define Z_PROBE_OFFSET_RANGE_MAX 0
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -624,13 +704,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
||||||
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
||||||
//define this to enable EEPROM support
|
//define this to enable EEPROM support
|
||||||
//#define EEPROM_SETTINGS
|
#define EEPROM_SETTINGS
|
||||||
|
|
||||||
#if ENABLED(EEPROM_SETTINGS)
|
#if ENABLED(EEPROM_SETTINGS)
|
||||||
// To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
|
// To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
|
||||||
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -639,38 +727,38 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
// Preheat Constants
|
// Preheat Constants
|
||||||
#define PLA_PREHEAT_HOTEND_TEMP 180
|
#define PLA_PREHEAT_HOTEND_TEMP 210
|
||||||
#define PLA_PREHEAT_HPB_TEMP 70
|
#define PLA_PREHEAT_HPB_TEMP 70
|
||||||
#define PLA_PREHEAT_FAN_SPEED 0 // Insert Value between 0 and 255
|
#define PLA_PREHEAT_FAN_SPEED 0 // Insert Value between 0 and 255
|
||||||
|
|
||||||
#define ABS_PREHEAT_HOTEND_TEMP 240
|
#define ABS_PREHEAT_HOTEND_TEMP 240
|
||||||
#define ABS_PREHEAT_HPB_TEMP 110
|
#define ABS_PREHEAT_HPB_TEMP 110
|
||||||
#define ABS_PREHEAT_FAN_SPEED 0 // Insert Value between 0 and 255
|
#define ABS_PREHEAT_FAN_SPEED 0 // Insert Value between 0 and 255
|
||||||
|
|
||||||
//==============================LCD and SD support=============================
|
//==============================LCD and SD support=============================
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
|
||||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
//#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)
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
|
||||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
||||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
|
@ -687,13 +775,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -708,7 +796,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
@ -725,12 +813,17 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// http://reprap.org/wiki/Mini_panel
|
// http://reprap.org/wiki/Mini_panel
|
||||||
//#define MINIPANEL
|
//#define MINIPANEL
|
||||||
|
|
||||||
|
// BQ SMART FULL GRAPHIC CONTROLLER
|
||||||
|
#define BQ_LCD_SMART_CONTROLLER
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* I2C Panels
|
* I2C Panels
|
||||||
*/
|
*/
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -744,7 +837,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
// SSD1306 OLED generic display support
|
// SSD1306 OLED generic display support
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define U8GLIB_SSD1306
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
|
@ -756,13 +849,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
//#define FAST_PWM_FAN
|
//#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
// which is not as annoying as with the hardware PWM. On the other hand, if this frequency
|
// which is not as annoying as with the hardware PWM. On the other hand, if this frequency
|
||||||
// is too low, you should also increment SOFT_PWM_SCALE.
|
// is too low, you should also increment SOFT_PWM_SCALE.
|
||||||
//#define FAN_SOFT_PWM
|
#define FAN_SOFT_PWM
|
||||||
|
|
||||||
// Incrementing this by 1 will double the software PWM frequency,
|
// Incrementing this by 1 will double the software PWM frequency,
|
||||||
// affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
|
// affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
|
||||||
|
@ -836,21 +929,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#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
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
|
|
||||||
//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.
|
#define MEASURED_UPPER_LIMIT 2.00 //upper limit factor used for sensor reading validation in mm
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
#define MEASURED_LOWER_LIMIT 1.60 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
659
Marlin/example_configurations/Hephestos_2/Configuration_adv.h
Normal file
659
Marlin/example_configurations/Hephestos_2/Configuration_adv.h
Normal file
|
@ -0,0 +1,659 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration_adv.h
|
||||||
|
*
|
||||||
|
* Advanced settings.
|
||||||
|
* Only change these if you know exactly what you're doing.
|
||||||
|
* Some of these settings can damage your printer if improperly set!
|
||||||
|
*
|
||||||
|
* Basic settings can be found in Configuration.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
#ifndef CONFIGURATION_ADV_H
|
||||||
|
#define CONFIGURATION_ADV_H
|
||||||
|
|
||||||
|
#include "Conditionals.h"
|
||||||
|
|
||||||
|
// @section temperature
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//=============================Thermal Settings ============================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
|
#if DISABLED(PIDTEMPBED)
|
||||||
|
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||||
|
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||||
|
#define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
|
*
|
||||||
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
|
*
|
||||||
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
|
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
||||||
|
* the firmware will halt the machine as a safety precaution.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
|
||||||
|
*/
|
||||||
|
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
||||||
|
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
||||||
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
||||||
|
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
||||||
|
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
||||||
|
* but only if the current temperature is far enough below the target for a reliable test.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
|
||||||
|
* WATCH_TEMP_INCREASE should not be below 2.
|
||||||
|
*/
|
||||||
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Thermal Protection parameters for the bed
|
||||||
|
* are like the above for the hotends.
|
||||||
|
* WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
|
||||||
|
*/
|
||||||
|
#if ENABLED(THERMAL_PROTECTION_BED)
|
||||||
|
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
||||||
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(PIDTEMP)
|
||||||
|
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||||
|
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||||
|
#define PID_ADD_EXTRUSION_RATE
|
||||||
|
#if ENABLED(PID_ADD_EXTRUSION_RATE)
|
||||||
|
#define DEFAULT_Kc (100) //heating power=Kc*(e_speed)
|
||||||
|
#define LPQ_MAX_LEN 50
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Automatic Temperature:
|
||||||
|
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
||||||
|
* The maximum buffered steps/sec of the extruder motor is called "se".
|
||||||
|
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
||||||
|
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
||||||
|
* mintemp and maxtemp. Turn this off by executing M109 without F*
|
||||||
|
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
||||||
|
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
||||||
|
*/
|
||||||
|
#define AUTOTEMP
|
||||||
|
#if ENABLED(AUTOTEMP)
|
||||||
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//Show Temperature ADC value
|
||||||
|
//The M105 command return, besides traditional information, the ADC value read from temperature sensors.
|
||||||
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
|
|
||||||
|
// @section extruder
|
||||||
|
|
||||||
|
// extruder run-out prevention.
|
||||||
|
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
|
||||||
|
//#define EXTRUDER_RUNOUT_PREVENT
|
||||||
|
#define EXTRUDER_RUNOUT_MINTEMP 190
|
||||||
|
#define EXTRUDER_RUNOUT_SECONDS 30.
|
||||||
|
#define EXTRUDER_RUNOUT_ESTEPS 14. //mm filament
|
||||||
|
#define EXTRUDER_RUNOUT_SPEED 1500. //extrusion speed
|
||||||
|
#define EXTRUDER_RUNOUT_EXTRUDE 100
|
||||||
|
|
||||||
|
// @section temperature
|
||||||
|
|
||||||
|
//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
|
||||||
|
//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
|
||||||
|
#define TEMP_SENSOR_AD595_OFFSET 0.0
|
||||||
|
#define TEMP_SENSOR_AD595_GAIN 1.0
|
||||||
|
|
||||||
|
//This is for controlling a fan to cool down the stepper drivers
|
||||||
|
//it will turn on when any driver is enabled
|
||||||
|
//and turn off after the set amount of seconds from last driver being disabled again
|
||||||
|
#define CONTROLLERFAN_PIN -1 //Pin used for the fan to cool controller (-1 to disable)
|
||||||
|
#define CONTROLLERFAN_SECS 60 //How many seconds, after all motors were disabled, the fan should run
|
||||||
|
#define CONTROLLERFAN_SPEED 255 // == full speed
|
||||||
|
|
||||||
|
// When first starting the main fan, run it at full speed for the
|
||||||
|
// given number of milliseconds. This gets the fan spinning reliably
|
||||||
|
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
|
||||||
|
//#define FAN_KICKSTART_TIME 100
|
||||||
|
|
||||||
|
// This defines the minimal speed for the main fan, run in PWM mode
|
||||||
|
// to enable uncomment and set minimal PWM speed for reliable running (1-255)
|
||||||
|
// if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM
|
||||||
|
//#define FAN_MIN_PWM 50
|
||||||
|
|
||||||
|
// @section extruder
|
||||||
|
|
||||||
|
// Extruder cooling fans
|
||||||
|
// Configure fan pin outputs to automatically turn on/off when the associated
|
||||||
|
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
|
||||||
|
// Multiple extruders can be assigned to the same pin in which case
|
||||||
|
// the fan will turn on when any selected extruder is above the threshold.
|
||||||
|
#define EXTRUDER_0_AUTO_FAN_PIN 11
|
||||||
|
#define EXTRUDER_1_AUTO_FAN_PIN 6
|
||||||
|
#define EXTRUDER_2_AUTO_FAN_PIN -1
|
||||||
|
#define EXTRUDER_3_AUTO_FAN_PIN -1
|
||||||
|
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
|
||||||
|
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
|
||||||
|
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//=============================Mechanical Settings===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
|
// @section homing
|
||||||
|
|
||||||
|
#define ENDSTOPS_ONLY_FOR_HOMING // If defined the endstops will only be used for homing
|
||||||
|
|
||||||
|
// @section extras
|
||||||
|
|
||||||
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
|
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
||||||
|
// Uncomment this define to utilize a separate stepper driver for each Z axis motor.
|
||||||
|
// Only a few motherboards support this, like RAMPS, which have dual extruder support (the 2nd, often unused, extruder driver is used
|
||||||
|
// to control the 2nd Z axis stepper motor). The pins are currently only defined for a RAMPS motherboards.
|
||||||
|
// On a RAMPS (or other 5 driver) motherboard, using this feature will limit you to using 1 extruder.
|
||||||
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
|
#if ENABLED(Z_DUAL_STEPPER_DRIVERS)
|
||||||
|
|
||||||
|
// 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.
|
||||||
|
// That way the machine is capable to align the bed during home, since both Z steppers are homed.
|
||||||
|
// There is also an implementation of M666 (software endstops adjustment) to this feature.
|
||||||
|
// After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
|
||||||
|
// 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.
|
||||||
|
// 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.
|
||||||
|
// Play a little bit with small adjustments (0.5mm) and check the behaviour.
|
||||||
|
// The M119 (endstops report) will start reporting the Z2 Endstop as well.
|
||||||
|
|
||||||
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
|
// Same again but for Y Axis.
|
||||||
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
|
// Define if the two Y drives need to rotate in opposite directions
|
||||||
|
#define INVERT_Y2_VS_Y_DIR true
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this for dual x-carriage printers.
|
||||||
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
|
// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
|
||||||
|
// allowing faster printing speeds.
|
||||||
|
//#define DUAL_X_CARRIAGE
|
||||||
|
#if ENABLED(DUAL_X_CARRIAGE)
|
||||||
|
// Configuration for second X-carriage
|
||||||
|
// Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
|
||||||
|
// the second x-carriage always homes to the maximum endstop.
|
||||||
|
#define X2_MIN_POS 80 // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
|
||||||
|
#define X2_MAX_POS 353 // set maximum to the distance between toolheads when both heads are homed
|
||||||
|
#define X2_HOME_DIR 1 // the second X-carriage always homes to the maximum endstop position
|
||||||
|
#define X2_HOME_POS X2_MAX_POS // default home position is the maximum carriage position
|
||||||
|
// However: In this mode the EXTRUDER_OFFSET_X value for the second extruder provides a software
|
||||||
|
// override for X2_HOME_POS. This also allow recalibration of the distance between the two endstops
|
||||||
|
// without modifying the firmware (through the "M218 T1 X???" command).
|
||||||
|
// Remember: you should set the second extruder x-offset to 0 in your slicer.
|
||||||
|
|
||||||
|
// Pins for second x-carriage stepper driver (defined here to avoid further complicating pins.h)
|
||||||
|
#define X2_ENABLE_PIN 29
|
||||||
|
#define X2_STEP_PIN 25
|
||||||
|
#define X2_DIR_PIN 23
|
||||||
|
|
||||||
|
// There are a few selectable movement modes for dual x-carriages using M605 S<mode>
|
||||||
|
// Mode 0: Full control. The slicer has full control over both x-carriages and can achieve optimal travel results
|
||||||
|
// as long as it supports dual x-carriages. (M605 S0)
|
||||||
|
// Mode 1: Auto-park mode. The firmware will automatically park and unpark the x-carriages on tool changes so
|
||||||
|
// that additional slicer support is not required. (M605 S1)
|
||||||
|
// Mode 2: Duplication mode. The firmware will transparently make the second x-carriage and extruder copy all
|
||||||
|
// actions of the first x-carriage. This allows the printer to print 2 arbitrary items at
|
||||||
|
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
|
||||||
|
|
||||||
|
// This is the default power-up mode which can be later using M605.
|
||||||
|
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
|
||||||
|
|
||||||
|
// Default settings in "Auto-park Mode"
|
||||||
|
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
|
||||||
|
#define TOOLCHANGE_UNPARK_ZLIFT 1 // the distance to raise Z axis when unparking an extruder
|
||||||
|
|
||||||
|
// Default x offset in duplication mode (typically set to half print bed width)
|
||||||
|
#define DEFAULT_DUPLICATION_X_OFFSET 100
|
||||||
|
|
||||||
|
#endif //DUAL_X_CARRIAGE
|
||||||
|
|
||||||
|
// @section homing
|
||||||
|
|
||||||
|
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
||||||
|
#define X_HOME_BUMP_MM 5
|
||||||
|
#define Y_HOME_BUMP_MM 5
|
||||||
|
#define Z_HOME_BUMP_MM 2
|
||||||
|
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||||
|
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
|
||||||
|
|
||||||
|
// When G28 is called, this option will make Y home before X
|
||||||
|
//#define HOME_Y_BEFORE_X
|
||||||
|
|
||||||
|
// @section machine
|
||||||
|
|
||||||
|
#define AXIS_RELATIVE_MODES {false, false, false, false}
|
||||||
|
|
||||||
|
// @section machine
|
||||||
|
|
||||||
|
//By default pololu step drivers require an active high signal. However, some high power drivers require an active low signal as step.
|
||||||
|
#define INVERT_X_STEP_PIN false
|
||||||
|
#define INVERT_Y_STEP_PIN false
|
||||||
|
#define INVERT_Z_STEP_PIN false
|
||||||
|
#define INVERT_E_STEP_PIN false
|
||||||
|
|
||||||
|
// Default stepper release if idle. Set to 0 to deactivate.
|
||||||
|
// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
|
||||||
|
// Time can be set by M18 and M84.
|
||||||
|
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
||||||
|
#define DISABLE_INACTIVE_X true
|
||||||
|
#define DISABLE_INACTIVE_Y true
|
||||||
|
#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished.
|
||||||
|
#define DISABLE_INACTIVE_E true
|
||||||
|
|
||||||
|
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
||||||
|
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
||||||
|
|
||||||
|
// @section lcd
|
||||||
|
|
||||||
|
#if ENABLED(ULTIPANEL)
|
||||||
|
#define MANUAL_FEEDRATE {50*60, 50*60, 4*60, 60} // Feedrates for manual moves along X, Y, Z, E from panel
|
||||||
|
#define ULTIPANEL_FEEDMULTIPLY // Comment to disable setting feedrate multiplier via encoder
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// @section extras
|
||||||
|
|
||||||
|
// minimum time in microseconds that a movement needs to take if the buffer is emptied.
|
||||||
|
#define DEFAULT_MINSEGMENTTIME 20000
|
||||||
|
|
||||||
|
// If defined the movements slow down when the look ahead buffer is only half full
|
||||||
|
#define SLOWDOWN
|
||||||
|
|
||||||
|
// Frequency limit
|
||||||
|
// See nophead's blog for more info
|
||||||
|
// Not working O
|
||||||
|
//#define XY_FREQUENCY_LIMIT 15
|
||||||
|
|
||||||
|
// Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
|
||||||
|
// of the buffer and all stops. This should not be much greater than zero and should only be changed
|
||||||
|
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
|
||||||
|
#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
|
||||||
|
|
||||||
|
// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
|
||||||
|
#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
|
||||||
|
|
||||||
|
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
||||||
|
#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])
|
||||||
|
|
||||||
|
// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
|
||||||
|
//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
|
||||||
|
|
||||||
|
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
||||||
|
//#define DIGIPOT_I2C
|
||||||
|
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
||||||
|
#define DIGIPOT_I2C_NUM_CHANNELS 8
|
||||||
|
// actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
|
#define DIGIPOT_I2C_MOTOR_CURRENTS {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0}
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//=============================Additional Features===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
|
#define ENCODER_RATE_MULTIPLIER // If defined, certain menu edit operations automatically multiply the steps when the encoder is moved quickly
|
||||||
|
#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
|
||||||
|
#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
|
||||||
|
|
||||||
|
//#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/
|
||||||
|
#define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again
|
||||||
|
|
||||||
|
// @section lcd
|
||||||
|
|
||||||
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
|
// around this by connecting a push button or single throw switch to the pin defined
|
||||||
|
// as SD_DETECT_PIN in your board's pins definitions.
|
||||||
|
// This setting should be disabled unless you are using a push button, pulling the pin to ground.
|
||||||
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
||||||
|
#define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
|
||||||
|
|
||||||
|
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
||||||
|
// 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.
|
||||||
|
// using:
|
||||||
|
#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
|
//#define LCD_PROGRESS_BAR
|
||||||
|
|
||||||
|
#if ENABLED(LCD_PROGRESS_BAR)
|
||||||
|
// Amount of time (ms) to show the bar
|
||||||
|
#define PROGRESS_BAR_BAR_TIME 2000
|
||||||
|
// Amount of time (ms) to show the status message
|
||||||
|
#define PROGRESS_BAR_MSG_TIME 3000
|
||||||
|
// Amount of time (ms) to retain the status message (0=forever)
|
||||||
|
#define PROGRESS_MSG_EXPIRE 0
|
||||||
|
// Enable this to show messages for MSG_TIME then hide them
|
||||||
|
//#define PROGRESS_MSG_ONCE
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// This allows hosts to request long names for files and folders with M33
|
||||||
|
#define LONG_FILENAME_HOST_SUPPORT
|
||||||
|
|
||||||
|
// This option allows you to abort SD printing when any endstop is triggered.
|
||||||
|
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||||
|
// To have any effect, endstops must be enabled during SD printing.
|
||||||
|
// With ENDSTOPS_ONLY_FOR_HOMING you must send "M120" to enable endstops.
|
||||||
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
|
// for dogm lcd displays you can choose some additional fonts:
|
||||||
|
#if ENABLED(DOGLCD)
|
||||||
|
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
|
||||||
|
// we don't have a big font for Cyrillic, Kana
|
||||||
|
//#define USE_BIG_EDIT_FONT
|
||||||
|
|
||||||
|
// If you have spare 2300Byte of progmem and want to use a
|
||||||
|
// smaller font on the Info-screen uncomment the next line.
|
||||||
|
#define USE_SMALL_INFOFONT
|
||||||
|
#endif // DOGLCD
|
||||||
|
|
||||||
|
// @section more
|
||||||
|
|
||||||
|
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
||||||
|
#define USE_WATCHDOG
|
||||||
|
|
||||||
|
#if ENABLED(USE_WATCHDOG)
|
||||||
|
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
||||||
|
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
||||||
|
// 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.
|
||||||
|
//#define WATCHDOG_RESET_MANUAL
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// @section lcd
|
||||||
|
|
||||||
|
// Babystepping enables the user to control the axis in tiny amounts, independently from the normal printing process
|
||||||
|
// it can e.g. be used to change z-positions in the print startup phase in real-time
|
||||||
|
// does not respect endstops!
|
||||||
|
//#define BABYSTEPPING
|
||||||
|
#if ENABLED(BABYSTEPPING)
|
||||||
|
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
||||||
|
//not implemented for deltabots!
|
||||||
|
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
||||||
|
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// @section extruder
|
||||||
|
|
||||||
|
// extruder advance constant (s2/mm3)
|
||||||
|
//
|
||||||
|
// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
|
||||||
|
//
|
||||||
|
// Hooke's law says: force = k * distance
|
||||||
|
// Bernoulli's principle says: v ^ 2 / 2 + g . h + pressure / density = constant
|
||||||
|
// so: v ^ 2 is proportional to number of steps we advance the extruder
|
||||||
|
//#define ADVANCE
|
||||||
|
|
||||||
|
#if ENABLED(ADVANCE)
|
||||||
|
#define EXTRUDER_ADVANCE_K .0
|
||||||
|
#define D_FILAMENT 2.85
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// @section extras
|
||||||
|
|
||||||
|
// Arc interpretation settings:
|
||||||
|
#define MM_PER_ARC_SEGMENT 1
|
||||||
|
#define N_ARC_CORRECTION 25
|
||||||
|
|
||||||
|
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
||||||
|
|
||||||
|
// @section temperature
|
||||||
|
|
||||||
|
// Control heater 0 and heater 1 in parallel.
|
||||||
|
//#define HEATERS_PARALLEL
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//================================= Buffers =================================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
|
// @section hidden
|
||||||
|
|
||||||
|
// The number of linear motions that can be in the plan at any give time.
|
||||||
|
// 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.
|
||||||
|
#if ENABLED(SDSUPPORT)
|
||||||
|
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
|
||||||
|
#else
|
||||||
|
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// @section more
|
||||||
|
|
||||||
|
//The ASCII buffer for receiving from the serial:
|
||||||
|
#define MAX_CMD_SIZE 96
|
||||||
|
#define BUFSIZE 4
|
||||||
|
|
||||||
|
// Bad Serial-connections can miss a received command by sending an 'ok'
|
||||||
|
// Therefore some clients abort after 30 seconds in a timeout.
|
||||||
|
// Some other clients start sending commands while receiving a 'wait'.
|
||||||
|
// This "wait" is only sent when the buffer is empty. 1 second is a good value here.
|
||||||
|
//#define NO_TIMEOUTS 1000 // Milliseconds
|
||||||
|
|
||||||
|
// Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
|
||||||
|
//#define ADVANCED_OK
|
||||||
|
|
||||||
|
// @section fwretract
|
||||||
|
|
||||||
|
// Firmware based and LCD controlled retract
|
||||||
|
// M207 and M208 can be used to define parameters for the retraction.
|
||||||
|
// The retraction can be called by the slicer using G10 and G11
|
||||||
|
// until then, intended retractions can be detected by moves that only extrude and the direction.
|
||||||
|
// the moves are than replaced by the firmware controlled ones.
|
||||||
|
|
||||||
|
//#define FWRETRACT //ONLY PARTIALLY TESTED
|
||||||
|
#if ENABLED(FWRETRACT)
|
||||||
|
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt
|
||||||
|
#define RETRACT_LENGTH 3 //default retract length (positive mm)
|
||||||
|
#define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change
|
||||||
|
#define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s)
|
||||||
|
#define RETRACT_ZLIFT 0 //default retract Z-lift
|
||||||
|
#define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering)
|
||||||
|
#define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change)
|
||||||
|
#define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Add support for experimental filament exchange support M600; requires display
|
||||||
|
#if ENABLED(ULTIPANEL)
|
||||||
|
//#define FILAMENTCHANGEENABLE
|
||||||
|
#if ENABLED(FILAMENTCHANGEENABLE)
|
||||||
|
#define FILAMENTCHANGE_XPOS 3
|
||||||
|
#define FILAMENTCHANGE_YPOS 3
|
||||||
|
#define FILAMENTCHANGE_ZADD 10
|
||||||
|
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||||
|
#define FILAMENTCHANGE_FINALRETRACT -100
|
||||||
|
#define AUTO_FILAMENT_CHANGE //This extrude filament until you press the button on LCD
|
||||||
|
#define AUTO_FILAMENT_CHANGE_LENGTH 0.04 //Extrusion length on automatic extrusion loop
|
||||||
|
#define AUTO_FILAMENT_CHANGE_FEEDRATE 300 //Extrusion feedrate (mm/min) on automatic extrusion loop
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/******************************************************************************\
|
||||||
|
* enable this section if you have TMC26X motor drivers.
|
||||||
|
* you need to import the TMC26XStepper library into the Arduino IDE for this
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
// @section tmc
|
||||||
|
|
||||||
|
//#define HAVE_TMCDRIVER
|
||||||
|
#if ENABLED(HAVE_TMCDRIVER)
|
||||||
|
|
||||||
|
//#define X_IS_TMC
|
||||||
|
#define X_MAX_CURRENT 1000 //in mA
|
||||||
|
#define X_SENSE_RESISTOR 91 //in mOhms
|
||||||
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
|
//#define X2_IS_TMC
|
||||||
|
#define X2_MAX_CURRENT 1000 //in mA
|
||||||
|
#define X2_SENSE_RESISTOR 91 //in mOhms
|
||||||
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
|
//#define Y_IS_TMC
|
||||||
|
#define Y_MAX_CURRENT 1000 //in mA
|
||||||
|
#define Y_SENSE_RESISTOR 91 //in mOhms
|
||||||
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
|
//#define Y2_IS_TMC
|
||||||
|
#define Y2_MAX_CURRENT 1000 //in mA
|
||||||
|
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
||||||
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
|
//#define Z_IS_TMC
|
||||||
|
#define Z_MAX_CURRENT 1000 //in mA
|
||||||
|
#define Z_SENSE_RESISTOR 91 //in mOhms
|
||||||
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
|
//#define Z2_IS_TMC
|
||||||
|
#define Z2_MAX_CURRENT 1000 //in mA
|
||||||
|
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
||||||
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
|
//#define E0_IS_TMC
|
||||||
|
#define E0_MAX_CURRENT 1000 //in mA
|
||||||
|
#define E0_SENSE_RESISTOR 91 //in mOhms
|
||||||
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
|
//#define E1_IS_TMC
|
||||||
|
#define E1_MAX_CURRENT 1000 //in mA
|
||||||
|
#define E1_SENSE_RESISTOR 91 //in mOhms
|
||||||
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
|
//#define E2_IS_TMC
|
||||||
|
#define E2_MAX_CURRENT 1000 //in mA
|
||||||
|
#define E2_SENSE_RESISTOR 91 //in mOhms
|
||||||
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
|
//#define E3_IS_TMC
|
||||||
|
#define E3_MAX_CURRENT 1000 //in mA
|
||||||
|
#define E3_SENSE_RESISTOR 91 //in mOhms
|
||||||
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/******************************************************************************\
|
||||||
|
* enable this section if you have L6470 motor drivers.
|
||||||
|
* you need to import the L6470 library into the Arduino IDE for this
|
||||||
|
******************************************************************************/
|
||||||
|
|
||||||
|
// @section l6470
|
||||||
|
|
||||||
|
//#define HAVE_L6470DRIVER
|
||||||
|
#if ENABLED(HAVE_L6470DRIVER)
|
||||||
|
|
||||||
|
//#define X_IS_L6470
|
||||||
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
|
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
|
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
|
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
//#define X2_IS_L6470
|
||||||
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
|
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
|
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
|
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
//#define Y_IS_L6470
|
||||||
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
|
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
|
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
|
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
//#define Y2_IS_L6470
|
||||||
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
|
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
|
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
|
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
//#define Z_IS_L6470
|
||||||
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
|
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
|
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
|
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
//#define Z2_IS_L6470
|
||||||
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
|
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
|
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
|
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
//#define E0_IS_L6470
|
||||||
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
|
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
|
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
|
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
//#define E1_IS_L6470
|
||||||
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
|
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
|
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
|
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
//#define E2_IS_L6470
|
||||||
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
|
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
|
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
|
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
//#define E3_IS_L6470
|
||||||
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
|
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
|
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
|
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "Conditionals.h"
|
||||||
|
#include "SanityCheck.h"
|
||||||
|
|
||||||
|
#endif //CONFIGURATION_ADV_H
|
8
Marlin/example_configurations/Hephestos_2/readme.md
Normal file
8
Marlin/example_configurations/Hephestos_2/readme.md
Normal file
|
@ -0,0 +1,8 @@
|
||||||
|
# Example Configuration for BQ [Hephestos 2](http://www.bq.com/uk/hephestos-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).
|
||||||
|
|
||||||
|
NOTE: The look and feel of the Hephestos 2 while navigating the LCD menu will change by using the original Marlin firmware.
|
||||||
|
|
||||||
|
## Changelog
|
||||||
|
* 2016/03/01 - Initial release
|
||||||
|
* 2016/03/21 - Activated four point auto leveling by default; updated miscellaneous z-probe values
|
|
@ -1,8 +1,47 @@
|
||||||
// Example configuration file for Vellemann K8200
|
/**
|
||||||
// tested on K8200 with VM8201 (Display)
|
* Marlin 3D Printer Firmware
|
||||||
// and Arduino 1.6.1 (Win) by @CONSULitAS, 2015-04-14
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
// https://github.com/CONSULitAS/Marlin-K8200/archive/K8200_stable_2015-04-14.zip
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Sample configuration file for Vellemann K8200
|
||||||
|
* tested on K8200 with VM8201 (Display)
|
||||||
|
* and Arduino 1.6.8 (Mac) by @CONSULitAS, 2016-02-21
|
||||||
|
* https://github.com/CONSULitAS/Marlin-K8200/archive/K8200_stable_2016-02-21.zip
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -12,8 +51,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -21,11 +62,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -52,7 +89,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// User-specified version info of this build to display in [Pronterface, etc] terminal window during
|
// User-specified version info of this build to display in [Pronterface, etc] terminal window during
|
||||||
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
|
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
|
||||||
// build by the user have been successfully uploaded into firmware.
|
// build by the user have been successfully uploaded into firmware.
|
||||||
#define STRING_CONFIG_H_AUTHOR "(K8200, CONSULitAS)" // Who made the changes.
|
#define STRING_CONFIG_H_AUTHOR "(K8200, @CONSULitAS)" // Who made the changes.
|
||||||
#define SHOW_BOOTSCREEN
|
#define SHOW_BOOTSCREEN
|
||||||
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
|
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
|
||||||
//#define STRING_SPLASH_LINE2 STRING_DISTRIBUTION_DATE // will be shown during bootup in line 2
|
//#define STRING_SPLASH_LINE2 STRING_DISTRIBUTION_DATE // will be shown during bootup in line 2
|
||||||
|
@ -80,11 +117,11 @@ Here are some standard links for getting your machine calibrated:
|
||||||
|
|
||||||
// Optional custom name for your RepStrap or other custom machine
|
// Optional custom name for your RepStrap or other custom machine
|
||||||
// Displayed in the LCD "Ready" message
|
// Displayed in the LCD "Ready" message
|
||||||
//#define CUSTOM_MACHINE_NAME "3D Printer"
|
#define CUSTOM_MACHINE_NAME "K8200"
|
||||||
|
|
||||||
// Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
|
// Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
|
||||||
// You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4)
|
// You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4)
|
||||||
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
#define MACHINE_UUID "2b7dea3b-844e-4ab1-aa96-bb6406607d6e" // K8200 standard config with VM8201 (Display)
|
||||||
|
|
||||||
// This defines the number of extruders
|
// This defines the number of extruders
|
||||||
// :[1,2,3,4]
|
// :[1,2,3,4]
|
||||||
|
@ -115,6 +152,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -134,6 +172,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -149,7 +188,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 5
|
#define TEMP_SENSOR_0 5
|
||||||
#define TEMP_SENSOR_1 0
|
#define TEMP_SENSOR_1 0
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
|
@ -183,14 +222,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define HEATER_3_MAXTEMP 275
|
#define HEATER_3_MAXTEMP 275
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
|
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
|
||||||
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
|
//#define BED_WATTS (12.0*12.0/1.1) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -202,6 +236,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
|
@ -212,11 +247,26 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
|
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
|
||||||
#define K1 0.95 //smoothing factor within the PID
|
#define K1 0.95 //smoothing factor within the PID
|
||||||
|
|
||||||
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
// Ultimaker
|
||||||
|
//#define DEFAULT_Kp 22.2
|
||||||
|
//#define DEFAULT_Ki 1.08
|
||||||
|
//#define DEFAULT_Kd 114
|
||||||
|
|
||||||
|
// MakerGear
|
||||||
|
//#define DEFAULT_Kp 7.0
|
||||||
|
//#define DEFAULT_Ki 0.1
|
||||||
|
//#define DEFAULT_Kd 12
|
||||||
|
|
||||||
|
// Mendel Parts V9 on 12V
|
||||||
|
//#define DEFAULT_Kp 63.0
|
||||||
|
//#define DEFAULT_Ki 2.25
|
||||||
|
//#define DEFAULT_Kd 440
|
||||||
|
|
||||||
// Vellemann K8200 Extruder - calculated with PID Autotune and tested
|
// Vellemann K8200 Extruder - calculated with PID Autotune and tested
|
||||||
#define DEFAULT_Kp 24.29
|
#define DEFAULT_Kp 24.29
|
||||||
#define DEFAULT_Ki 1.58
|
#define DEFAULT_Ki 1.58
|
||||||
#define DEFAULT_Kd 93.51
|
#define DEFAULT_Kd 93.51
|
||||||
|
|
||||||
#endif // PIDTEMP
|
#endif // PIDTEMP
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -231,7 +281,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
|
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
|
||||||
// shouldn't use bed PID until someone else verifies your hardware works.
|
// shouldn't use bed PID until someone else verifies your hardware works.
|
||||||
// If this is enabled, find your own PID constants below.
|
// If this is enabled, find your own PID constants below.
|
||||||
//#define PIDTEMPBED
|
#define PIDTEMPBED
|
||||||
|
|
||||||
//#define BED_LIMIT_SWITCHING
|
//#define BED_LIMIT_SWITCHING
|
||||||
|
|
||||||
|
@ -241,19 +291,31 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
|
|
||||||
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
||||||
|
|
||||||
//Vellemann K8200 PCB heatbed with standard PCU at 60 degreesC - calculated with PID Autotune and tested
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
|
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||||
|
//#define DEFAULT_bedKp 10.00
|
||||||
|
//#define DEFAULT_bedKi .023
|
||||||
|
//#define DEFAULT_bedKd 305.4
|
||||||
|
|
||||||
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from pidautotune
|
//from pidautotune
|
||||||
|
//#define DEFAULT_bedKp 97.1
|
||||||
|
//#define DEFAULT_bedKi 1.41
|
||||||
|
//#define DEFAULT_bedKd 1675.16
|
||||||
|
|
||||||
|
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
||||||
|
|
||||||
|
// Vellemann K8200 PCB heatbed with standard PCU at 60 degreesC - calculated with PID Autotune and tested
|
||||||
|
// from pidautotune
|
||||||
#define DEFAULT_bedKp 341.88
|
#define DEFAULT_bedKp 341.88
|
||||||
#define DEFAULT_bedKi 25.32
|
#define DEFAULT_bedKi 25.32
|
||||||
#define DEFAULT_bedKd 1153.89
|
#define DEFAULT_bedKd 1153.89
|
||||||
|
|
||||||
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
|
||||||
#endif // PIDTEMPBED
|
#endif // PIDTEMPBED
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
@ -272,16 +334,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -302,8 +363,22 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
#define USE_XMIN_PLUG
|
||||||
|
#define USE_YMIN_PLUG
|
||||||
|
#define USE_ZMIN_PLUG
|
||||||
|
//#define USE_XMAX_PLUG
|
||||||
|
//#define USE_YMAX_PLUG
|
||||||
|
//#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -326,13 +401,53 @@ const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
#define DISABLE_MAX_ENDSTOPS
|
|
||||||
//#define DISABLE_MIN_ENDSTOPS
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -342,11 +457,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z true
|
#define DISABLE_Z false // not for K8200 -> looses Steps
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -357,7 +474,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
|
// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
|
||||||
#define INVERT_X_DIR false
|
#define INVERT_X_DIR false
|
||||||
#define INVERT_Y_DIR false
|
#define INVERT_Y_DIR false // was true -> why for K8200?
|
||||||
#define INVERT_Z_DIR false
|
#define INVERT_Z_DIR false
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
@ -369,6 +486,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define INVERT_E3_DIR true
|
#define INVERT_E3_DIR true
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
@ -404,24 +523,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
|
||||||
#define MESH_MIN_Y 10
|
#define MESH_MIN_Y 10
|
||||||
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
|
#define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -432,7 +553,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
//#define DEBUG_LEVELING_FEATURE
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
|
@ -444,7 +565,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -458,7 +579,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define FRONT_PROBE_BED_POSITION 20
|
#define FRONT_PROBE_BED_POSITION 20
|
||||||
#define BACK_PROBE_BED_POSITION 170
|
#define BACK_PROBE_BED_POSITION 170
|
||||||
|
|
||||||
#define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
|
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
|
||||||
|
|
||||||
// Set the number of grid points per dimension.
|
// Set the number of grid points per dimension.
|
||||||
// You probably don't need more than 3 (squared=9).
|
// You probably don't need more than 3 (squared=9).
|
||||||
|
@ -466,25 +587,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X 15
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y 180
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X 15
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y 20
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X 170
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
|
@ -492,16 +625,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
||||||
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
//#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
|
@ -515,37 +661,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
|
||||||
|
@ -579,7 +694,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#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.
|
#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.
|
||||||
|
|
||||||
#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
|
#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
|
||||||
#define DEFAULT_RETRACT_ACCELERATION 1000 // E acceleration in mm/s^2 for retracts
|
#define DEFAULT_RETRACT_ACCELERATION 1000 // E acceleration in mm/s^2 for retracts
|
||||||
#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
|
#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
|
||||||
|
|
||||||
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
|
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
|
||||||
|
@ -619,6 +734,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -639,26 +762,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // K8200: for Display VM8201 // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // K8200: for Display VM8201 // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
|
||||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
//#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)
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
|
||||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
||||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
#define ULTIMAKERCONTROLLER // K8200: for Display VM8201 // as available from the Ultimaker online store.
|
#define ULTIMAKERCONTROLLER // K8200: for Display VM8201 // as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
|
@ -675,13 +798,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -696,7 +819,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
@ -719,6 +842,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -732,7 +857,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
// SSD1306 OLED generic display support
|
// SSD1306 OLED generic display support
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define U8GLIB_SSD1306
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
|
@ -744,7 +869,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
//#define FAST_PWM_FAN
|
//#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
@ -824,21 +949,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#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
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
|
|
||||||
//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.
|
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
|
@ -1,3 +1,41 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Sample configuration file for Vellemann K8200
|
||||||
|
// tested on K8200 with VM8201 (Display)
|
||||||
|
// and Arduino 1.6.8 (Mac) by @CONSULitAS, 2016-02-21
|
||||||
|
// https://github.com/CONSULitAS/Marlin-K8200/archive/K8200_stable_2016-02-21.zip
|
||||||
|
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration_adv.h
|
||||||
|
*
|
||||||
|
* Advanced settings.
|
||||||
|
* Only change these if you know exactly what you're doing.
|
||||||
|
* Some of these settings can damage your printer if improperly set!
|
||||||
|
*
|
||||||
|
* Basic settings can be found in Configuration.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
|
|
||||||
|
@ -9,43 +47,54 @@
|
||||||
//=============================Thermal Settings ============================
|
//=============================Thermal Settings ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
#if DISABLED(PIDTEMPBED)
|
||||||
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||||
|
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||||
|
#define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection parameters
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
|
*
|
||||||
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
|
*
|
||||||
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
|
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
||||||
|
* the firmware will halt the machine as a safety precaution.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
|
||||||
*/
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
||||||
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
#define THERMAL_PROTECTION_PERIOD 60 // Seconds
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 8 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* but only if the current temperature is far enough below the target for a reliable test.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
|
||||||
|
* WATCH_TEMP_INCREASE should not be below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 16 // Seconds
|
#define WATCH_TEMP_PERIOD 30 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 4 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 4 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Thermal Protection parameters for the bed
|
||||||
|
* are like the above for the hotends.
|
||||||
|
* WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
|
||||||
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_BED)
|
#if ENABLED(THERMAL_PROTECTION_BED)
|
||||||
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
|
||||||
* Automatic Temperature:
|
|
||||||
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
|
||||||
* The maximum buffered steps/sec of the extruder motor is called "se".
|
|
||||||
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
|
||||||
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
|
||||||
* mintemp and maxtemp. Turn this off by excuting M109 without F*
|
|
||||||
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
|
||||||
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
|
||||||
*/
|
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||||
|
@ -56,14 +105,16 @@
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
|
* Automatic Temperature:
|
||||||
//The maximum buffered steps/sec of the extruder motor are called "se".
|
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
||||||
//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
|
* The maximum buffered steps/sec of the extruder motor is called "se".
|
||||||
// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
|
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
||||||
// you exit the value by any M109 without F*
|
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
||||||
// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
|
* mintemp and maxtemp. Turn this off by executing M109 without F*
|
||||||
// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
||||||
|
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
||||||
|
*/
|
||||||
#define AUTOTEMP
|
#define AUTOTEMP
|
||||||
#if ENABLED(AUTOTEMP)
|
#if ENABLED(AUTOTEMP)
|
||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
|
@ -101,12 +152,12 @@
|
||||||
// When first starting the main fan, run it at full speed for the
|
// When first starting the main fan, run it at full speed for the
|
||||||
// given number of milliseconds. This gets the fan spinning reliably
|
// given number of milliseconds. This gets the fan spinning reliably
|
||||||
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
|
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
|
||||||
//#define FAN_KICKSTART_TIME 100
|
#define FAN_KICKSTART_TIME 500
|
||||||
|
|
||||||
// This defines the minimal speed for the main fan, run in PWM mode
|
// This defines the minimal speed for the main fan, run in PWM mode
|
||||||
// to enable uncomment and set minimal PWM speed for reliable running (1-255)
|
// to enable uncomment and set minimal PWM speed for reliable running (1-255)
|
||||||
// if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM
|
// if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM
|
||||||
#define FAN_MIN_PWM 50 // K8200: fan stops running at about 35 to 40 (of 255)
|
#define FAN_MIN_PWM 50
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -156,9 +207,7 @@
|
||||||
//#define Z_DUAL_ENDSTOPS
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_MAX_PIN 36 //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36)
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
const bool Z2_MAX_ENDSTOP_INVERTING = false;
|
|
||||||
#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.
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
#endif // Z_DUAL_STEPPER_DRIVERS
|
||||||
|
@ -220,9 +269,9 @@
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
||||||
#define X_HOME_BUMP_MM 5
|
#define X_HOME_BUMP_MM 5
|
||||||
#define Y_HOME_BUMP_MM 5
|
#define Y_HOME_BUMP_MM 5
|
||||||
#define Z_HOME_BUMP_MM 3
|
#define Z_HOME_BUMP_MM 2
|
||||||
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
#define HOMING_BUMP_DIVISOR {4, 4, 8} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
||||||
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
|
#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
|
||||||
|
|
||||||
// When G28 is called, this option will make Y home before X
|
// When G28 is called, this option will make Y home before X
|
||||||
//#define HOME_Y_BEFORE_X
|
//#define HOME_Y_BEFORE_X
|
||||||
|
@ -240,7 +289,13 @@
|
||||||
#define INVERT_E_STEP_PIN false
|
#define INVERT_E_STEP_PIN false
|
||||||
|
|
||||||
// Default stepper release if idle. Set to 0 to deactivate.
|
// Default stepper release if idle. Set to 0 to deactivate.
|
||||||
|
// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
|
||||||
|
// Time can be set by M18 and M84.
|
||||||
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
||||||
|
#define DISABLE_INACTIVE_X true
|
||||||
|
#define DISABLE_INACTIVE_Y true
|
||||||
|
#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished.
|
||||||
|
#define DISABLE_INACTIVE_E true
|
||||||
|
|
||||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
||||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
||||||
|
@ -276,6 +331,9 @@
|
||||||
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
||||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||||
|
|
||||||
|
// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
|
||||||
|
//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
|
||||||
|
|
||||||
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
||||||
|
@ -311,10 +369,10 @@
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
||||||
// 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.
|
// 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.
|
||||||
// using:
|
// using:
|
||||||
//#define MENU_ADDAUTOSTART
|
#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
//#define LCD_PROGRESS_BAR
|
#define LCD_PROGRESS_BAR
|
||||||
|
|
||||||
#if ENABLED(LCD_PROGRESS_BAR)
|
#if ENABLED(LCD_PROGRESS_BAR)
|
||||||
// Amount of time (ms) to show the bar
|
// Amount of time (ms) to show the bar
|
||||||
|
@ -328,7 +386,7 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// This allows hosts to request long names for files and folders with M33
|
// This allows hosts to request long names for files and folders with M33
|
||||||
//#define LONG_FILENAME_HOST_SUPPORT
|
#define LONG_FILENAME_HOST_SUPPORT
|
||||||
|
|
||||||
// This option allows you to abort SD printing when any endstop is triggered.
|
// This option allows you to abort SD printing when any endstop is triggered.
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
||||||
|
@ -349,17 +407,16 @@
|
||||||
//#define USE_SMALL_INFOFONT
|
//#define USE_SMALL_INFOFONT
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
|
|
||||||
// @section more
|
// @section more
|
||||||
|
|
||||||
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
||||||
//#define USE_WATCHDOG
|
#define USE_WATCHDOG
|
||||||
|
|
||||||
#if ENABLED(USE_WATCHDOG)
|
#if ENABLED(USE_WATCHDOG)
|
||||||
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
||||||
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
||||||
// 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.
|
// 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.
|
||||||
//#define WATCHDOG_RESET_MANUAL
|
//#define WATCHDOG_RESET_MANUAL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
@ -367,9 +424,10 @@
|
||||||
// Babystepping enables the user to control the axis in tiny amounts, independently from the normal printing process
|
// Babystepping enables the user to control the axis in tiny amounts, independently from the normal printing process
|
||||||
// it can e.g. be used to change z-positions in the print startup phase in real-time
|
// it can e.g. be used to change z-positions in the print startup phase in real-time
|
||||||
// does not respect endstops!
|
// does not respect endstops!
|
||||||
//#define BABYSTEPPING
|
#define BABYSTEPPING
|
||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
||||||
|
//not implemented for deltabots!
|
||||||
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
||||||
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
||||||
#endif
|
#endif
|
||||||
|
@ -388,7 +446,6 @@
|
||||||
#if ENABLED(ADVANCE)
|
#if ENABLED(ADVANCE)
|
||||||
#define EXTRUDER_ADVANCE_K .0
|
#define EXTRUDER_ADVANCE_K .0
|
||||||
#define D_FILAMENT 2.85
|
#define D_FILAMENT 2.85
|
||||||
#define STEPS_MM_E 836
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
@ -397,7 +454,7 @@
|
||||||
#define MM_PER_ARC_SEGMENT 1
|
#define MM_PER_ARC_SEGMENT 1
|
||||||
#define N_ARC_CORRECTION 25
|
#define N_ARC_CORRECTION 25
|
||||||
|
|
||||||
const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
const unsigned int dropsegments = 2; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
|
@ -415,7 +472,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
|
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
|
||||||
#else
|
#else
|
||||||
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
|
#define BLOCK_BUFFER_SIZE 32 // maximize block buffer
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section more
|
// @section more
|
||||||
|
@ -462,12 +519,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
#define FILAMENTCHANGE_ZADD 10
|
#define FILAMENTCHANGE_ZADD 10
|
||||||
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||||
#define FILAMENTCHANGE_FINALRETRACT -100
|
#define FILAMENTCHANGE_FINALRETRACT -100
|
||||||
|
#define AUTO_FILAMENT_CHANGE //This extrude filament until you press the button on LCD
|
||||||
|
#define AUTO_FILAMENT_CHANGE_LENGTH 0.04 //Extrusion length on automatic extrusion loop
|
||||||
|
#define AUTO_FILAMENT_CHANGE_FEEDRATE 300 //Extrusion feedrate (mm/min) on automatic extrusion loop
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have TMC26X motor drivers.
|
* enable this section if you have TMC26X motor drivers.
|
||||||
* you need to import the TMC26XStepper library into the arduino IDE for this
|
* you need to import the TMC26XStepper library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section tmc
|
// @section tmc
|
||||||
|
@ -475,52 +535,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_TMCDRIVER
|
//#define HAVE_TMCDRIVER
|
||||||
#if ENABLED(HAVE_TMCDRIVER)
|
#if ENABLED(HAVE_TMCDRIVER)
|
||||||
|
|
||||||
//#define X_IS_TMC
|
//#define X_IS_TMC
|
||||||
#define X_MAX_CURRENT 1000 //in mA
|
#define X_MAX_CURRENT 1000 //in mA
|
||||||
#define X_SENSE_RESISTOR 91 //in mOhms
|
#define X_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define X2_IS_TMC
|
//#define X2_IS_TMC
|
||||||
#define X2_MAX_CURRENT 1000 //in mA
|
#define X2_MAX_CURRENT 1000 //in mA
|
||||||
#define X2_SENSE_RESISTOR 91 //in mOhms
|
#define X2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y_IS_TMC
|
//#define Y_IS_TMC
|
||||||
#define Y_MAX_CURRENT 1000 //in mA
|
#define Y_MAX_CURRENT 1000 //in mA
|
||||||
#define Y_SENSE_RESISTOR 91 //in mOhms
|
#define Y_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y2_IS_TMC
|
//#define Y2_IS_TMC
|
||||||
#define Y2_MAX_CURRENT 1000 //in mA
|
#define Y2_MAX_CURRENT 1000 //in mA
|
||||||
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z_IS_TMC
|
//#define Z_IS_TMC
|
||||||
#define Z_MAX_CURRENT 1000 //in mA
|
#define Z_MAX_CURRENT 1000 //in mA
|
||||||
#define Z_SENSE_RESISTOR 91 //in mOhms
|
#define Z_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z2_IS_TMC
|
//#define Z2_IS_TMC
|
||||||
#define Z2_MAX_CURRENT 1000 //in mA
|
#define Z2_MAX_CURRENT 1000 //in mA
|
||||||
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E0_IS_TMC
|
//#define E0_IS_TMC
|
||||||
#define E0_MAX_CURRENT 1000 //in mA
|
#define E0_MAX_CURRENT 1000 //in mA
|
||||||
#define E0_SENSE_RESISTOR 91 //in mOhms
|
#define E0_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E1_IS_TMC
|
//#define E1_IS_TMC
|
||||||
#define E1_MAX_CURRENT 1000 //in mA
|
#define E1_MAX_CURRENT 1000 //in mA
|
||||||
#define E1_SENSE_RESISTOR 91 //in mOhms
|
#define E1_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E2_IS_TMC
|
//#define E2_IS_TMC
|
||||||
#define E2_MAX_CURRENT 1000 //in mA
|
#define E2_MAX_CURRENT 1000 //in mA
|
||||||
#define E2_SENSE_RESISTOR 91 //in mOhms
|
#define E2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E3_IS_TMC
|
//#define E3_IS_TMC
|
||||||
#define E3_MAX_CURRENT 1000 //in mA
|
#define E3_MAX_CURRENT 1000 //in mA
|
||||||
#define E3_SENSE_RESISTOR 91 //in mOhms
|
#define E3_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
|
@ -529,7 +589,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have L6470 motor drivers.
|
* enable this section if you have L6470 motor drivers.
|
||||||
* you need to import the L6470 library into the arduino IDE for this
|
* you need to import the L6470 library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section l6470
|
// @section l6470
|
||||||
|
@ -537,63 +597,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_L6470DRIVER
|
//#define HAVE_L6470DRIVER
|
||||||
#if ENABLED(HAVE_L6470DRIVER)
|
#if ENABLED(HAVE_L6470DRIVER)
|
||||||
|
|
||||||
//#define X_IS_L6470
|
//#define X_IS_L6470
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define X2_IS_L6470
|
//#define X2_IS_L6470
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y_IS_L6470
|
//#define Y_IS_L6470
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y2_IS_L6470
|
//#define Y2_IS_L6470
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z_IS_L6470
|
//#define Z_IS_L6470
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z2_IS_L6470
|
//#define Z2_IS_L6470
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E0_IS_L6470
|
//#define E0_IS_L6470
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E1_IS_L6470
|
//#define E1_IS_L6470
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E2_IS_L6470
|
//#define E2_IS_L6470
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E3_IS_L6470
|
//#define E3_IS_L6470
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,40 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -7,8 +44,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -16,11 +55,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -110,6 +145,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -129,6 +165,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -144,7 +181,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 1
|
#define TEMP_SENSOR_0 1
|
||||||
#define TEMP_SENSOR_1 0
|
#define TEMP_SENSOR_1 0
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
|
@ -178,14 +215,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define HEATER_3_MAXTEMP 275
|
#define HEATER_3_MAXTEMP 275
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
|
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
|
||||||
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
|
//#define BED_WATTS (12.0*12.0/1.1) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -197,6 +229,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
|
@ -247,19 +280,19 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
|
|
||||||
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||||
#define DEFAULT_bedKp 10.00
|
#define DEFAULT_bedKp 10.00
|
||||||
#define DEFAULT_bedKi .023
|
#define DEFAULT_bedKi .023
|
||||||
#define DEFAULT_bedKd 305.4
|
#define DEFAULT_bedKd 305.4
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from pidautotune
|
//from pidautotune
|
||||||
//#define DEFAULT_bedKp 97.1
|
//#define DEFAULT_bedKp 97.1
|
||||||
//#define DEFAULT_bedKi 1.41
|
//#define DEFAULT_bedKi 1.41
|
||||||
|
@ -284,16 +317,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -314,8 +346,22 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
#define USE_XMIN_PLUG
|
||||||
|
#define USE_YMIN_PLUG
|
||||||
|
#define USE_ZMIN_PLUG
|
||||||
|
//#define USE_XMAX_PLUG
|
||||||
|
//#define USE_YMAX_PLUG
|
||||||
|
//#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -338,13 +384,53 @@ const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
//#define DISABLE_MAX_ENDSTOPS
|
|
||||||
//#define DISABLE_MIN_ENDSTOPS
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -354,11 +440,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z false
|
#define DISABLE_Z false
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -381,6 +469,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define INVERT_E3_DIR false
|
#define INVERT_E3_DIR false
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
@ -416,24 +506,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
|
||||||
#define MESH_MIN_Y 10
|
#define MESH_MIN_Y 10
|
||||||
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
|
#define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -442,10 +534,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section bedlevel
|
// @section bedlevel
|
||||||
|
|
||||||
|
|
||||||
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
//#define DEBUG_LEVELING_FEATURE
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
|
@ -457,7 +548,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -471,7 +562,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define FRONT_PROBE_BED_POSITION 20
|
#define FRONT_PROBE_BED_POSITION 20
|
||||||
#define BACK_PROBE_BED_POSITION 170
|
#define BACK_PROBE_BED_POSITION 170
|
||||||
|
|
||||||
#define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
|
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
|
||||||
|
|
||||||
// Set the number of grid points per dimension.
|
// Set the number of grid points per dimension.
|
||||||
// You probably don't need more than 3 (squared=9).
|
// You probably don't need more than 3 (squared=9).
|
||||||
|
@ -479,25 +570,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X 15
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y 180
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X 15
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y 20
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X 170
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
|
@ -505,16 +608,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
||||||
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
//#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
|
@ -528,37 +644,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
|
||||||
|
@ -632,6 +717,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -652,13 +745,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
@ -666,11 +759,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define ULTRA_LCD //general LCD support, also 16x2
|
#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
//#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)
|
||||||
#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
||||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
|
@ -687,13 +781,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -708,7 +802,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
@ -731,6 +825,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -744,7 +840,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
// SSD1306 OLED generic display support
|
// SSD1306 OLED generic display support
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define U8GLIB_SSD1306
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
|
@ -756,7 +852,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
//#define FAST_PWM_FAN
|
//#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
@ -836,21 +932,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#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
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
|
|
||||||
//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.
|
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
|
@ -1,3 +1,40 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -7,8 +44,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -16,11 +55,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -110,6 +145,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -129,6 +165,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -144,7 +181,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 1 // DGlass3D = 5; RigidBot = 1; 3DSv6 = 5
|
#define TEMP_SENSOR_0 1 // DGlass3D = 5; RigidBot = 1; 3DSv6 = 5
|
||||||
#define TEMP_SENSOR_1 0
|
#define TEMP_SENSOR_1 0
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
|
@ -178,14 +215,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define HEATER_3_MAXTEMP 275
|
#define HEATER_3_MAXTEMP 275
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
|
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
|
||||||
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
|
//#define BED_WATTS (12.0*12.0/1.1) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -197,6 +229,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
|
@ -219,6 +252,11 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//#define DEFAULT_Ki 0.85
|
//#define DEFAULT_Ki 0.85
|
||||||
//#define DEFAULT_Kd 245
|
//#define DEFAULT_Kd 245
|
||||||
|
|
||||||
|
// E3D w/ rigidbot cartridge
|
||||||
|
//#define DEFAULT_Kp 16.30
|
||||||
|
//#define DEFAULT_Ki 0.95
|
||||||
|
//#define DEFAULT_Kd 69.69
|
||||||
|
|
||||||
#endif // PIDTEMP
|
#endif // PIDTEMP
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -243,10 +281,10 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
|
|
||||||
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
||||||
|
|
||||||
//RigidBot, from pid autotune
|
//RigidBot, from pid autotune
|
||||||
|
@ -273,16 +311,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -297,11 +334,28 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Uncomment this option to enable CoreXY kinematics
|
// Uncomment this option to enable CoreXY kinematics
|
||||||
//#define COREXY
|
//#define COREXY
|
||||||
|
|
||||||
|
// Uncomment this option to enable CoreXZ kinematics
|
||||||
|
//#define COREXZ
|
||||||
|
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
#define USE_XMIN_PLUG
|
||||||
|
#define USE_YMIN_PLUG
|
||||||
|
#define USE_ZMIN_PLUG
|
||||||
|
//#define USE_XMAX_PLUG
|
||||||
|
//#define USE_YMAX_PLUG
|
||||||
|
//#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -324,13 +378,53 @@ const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
//#define DISABLE_MAX_ENDSTOPS
|
|
||||||
//#define DISABLE_MIN_ENDSTOPS
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -340,11 +434,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z false
|
#define DISABLE_Z false
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -367,6 +463,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define INVERT_E3_DIR false
|
#define INVERT_E3_DIR false
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
@ -402,24 +500,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
|
||||||
#define MESH_MIN_Y 10
|
#define MESH_MIN_Y 10
|
||||||
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
|
#define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -430,7 +530,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
//#define DEBUG_LEVELING_FEATURE
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
//#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
//#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
|
@ -442,7 +542,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -456,7 +556,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define FRONT_PROBE_BED_POSITION 20
|
#define FRONT_PROBE_BED_POSITION 20
|
||||||
#define BACK_PROBE_BED_POSITION 170
|
#define BACK_PROBE_BED_POSITION 170
|
||||||
|
|
||||||
#define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
|
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
|
||||||
|
|
||||||
// Set the number of grid points per dimension.
|
// Set the number of grid points per dimension.
|
||||||
// You probably don't need more than 3 (squared=9).
|
// You probably don't need more than 3 (squared=9).
|
||||||
|
@ -464,25 +564,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X 15
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y 180
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X 15
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y 20
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X 170
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
|
@ -490,16 +602,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
||||||
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
//#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
|
@ -513,37 +638,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
|
||||||
|
@ -611,13 +705,21 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
||||||
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
||||||
//define this to enable EEPROM support
|
//define this to enable EEPROM support
|
||||||
//#define EEPROM_SETTINGS
|
#define EEPROM_SETTINGS
|
||||||
|
|
||||||
#if ENABLED(EEPROM_SETTINGS)
|
#if ENABLED(EEPROM_SETTINGS)
|
||||||
// To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
|
// To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
|
||||||
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -638,26 +740,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
|
||||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
#define SPI_SPEED SPI_EIGHTH_SPEED // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
|
||||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
||||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
|
@ -674,13 +776,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -695,7 +797,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//
|
//
|
||||||
// RigidBoard: To rewire this for a RigidBot see http://rigidtalk.com/wiki/index.php?title=LCD_Smart_Controller
|
// RigidBoard: To rewire this for a RigidBot see http://rigidtalk.com/wiki/index.php?title=LCD_Smart_Controller
|
||||||
//
|
//
|
||||||
|
@ -711,6 +813,10 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
||||||
//#define RA_CONTROL_PANEL
|
//#define RA_CONTROL_PANEL
|
||||||
|
|
||||||
|
// The MakerLab Mini Panel with graphic controller and SD support
|
||||||
|
// http://reprap.org/wiki/Mini_panel
|
||||||
|
//#define MINIPANEL
|
||||||
|
|
||||||
// RigidBot Panel V1.0
|
// RigidBot Panel V1.0
|
||||||
// http://www.inventapart.com/
|
// http://www.inventapart.com/
|
||||||
#define RIGIDBOT_PANEL
|
#define RIGIDBOT_PANEL
|
||||||
|
@ -721,6 +827,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -734,7 +842,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
// SSD1306 OLED generic display support
|
// SSD1306 OLED generic display support
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define U8GLIB_SSD1306
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
|
@ -746,7 +854,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
//#define FAST_PWM_FAN
|
//#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
@ -826,21 +934,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#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
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
|
|
||||||
//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.
|
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
|
@ -1,3 +1,35 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration_adv.h
|
||||||
|
*
|
||||||
|
* Advanced settings.
|
||||||
|
* Only change these if you know exactly what you're doing.
|
||||||
|
* Some of these settings can damage your printer if improperly set!
|
||||||
|
*
|
||||||
|
* Basic settings can be found in Configuration.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
|
|
||||||
|
@ -9,13 +41,26 @@
|
||||||
//=============================Thermal Settings ============================
|
//=============================Thermal Settings ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
#if DISABLED(PIDTEMPBED)
|
||||||
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||||
|
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||||
|
#define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection parameters
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
|
*
|
||||||
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
|
*
|
||||||
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
|
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
||||||
|
* the firmware will halt the machine as a safety precaution.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
|
||||||
*/
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
||||||
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
||||||
|
@ -26,11 +71,19 @@
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* but only if the current temperature is far enough below the target for a reliable test.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
|
||||||
|
* WATCH_TEMP_INCREASE should not be below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 16 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 4 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Thermal Protection parameters for the bed
|
||||||
|
* are like the above for the hotends.
|
||||||
|
* WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
|
||||||
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_BED)
|
#if ENABLED(THERMAL_PROTECTION_BED)
|
||||||
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
@ -52,7 +105,7 @@
|
||||||
* The maximum buffered steps/sec of the extruder motor is called "se".
|
* The maximum buffered steps/sec of the extruder motor is called "se".
|
||||||
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
||||||
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
||||||
* mintemp and maxtemp. Turn this off by excuting M109 without F*
|
* mintemp and maxtemp. Turn this off by executing M109 without F*
|
||||||
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
||||||
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
||||||
*/
|
*/
|
||||||
|
@ -148,9 +201,7 @@
|
||||||
//#define Z_DUAL_ENDSTOPS
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_MAX_PIN 36 //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36)
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
const bool Z2_MAX_ENDSTOP_INVERTING = false;
|
|
||||||
#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.
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
#endif // Z_DUAL_STEPPER_DRIVERS
|
||||||
|
@ -232,7 +283,13 @@
|
||||||
#define INVERT_E_STEP_PIN false
|
#define INVERT_E_STEP_PIN false
|
||||||
|
|
||||||
// Default stepper release if idle. Set to 0 to deactivate.
|
// Default stepper release if idle. Set to 0 to deactivate.
|
||||||
|
// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
|
||||||
|
// Time can be set by M18 and M84.
|
||||||
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
||||||
|
#define DISABLE_INACTIVE_X true
|
||||||
|
#define DISABLE_INACTIVE_Y true
|
||||||
|
#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished.
|
||||||
|
#define DISABLE_INACTIVE_E true
|
||||||
|
|
||||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
||||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
||||||
|
@ -268,6 +325,9 @@
|
||||||
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
||||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||||
|
|
||||||
|
// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
|
||||||
|
//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
|
||||||
|
|
||||||
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
||||||
|
@ -279,9 +339,9 @@
|
||||||
//=============================Additional Features===========================
|
//=============================Additional Features===========================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define ENCODER_RATE_MULTIPLIER // If defined, certain menu edit operations automatically multiply the steps when the encoder is moved quickly
|
//#define ENCODER_RATE_MULTIPLIER // If defined, certain menu edit operations automatically multiply the steps when the encoder is moved quickly
|
||||||
#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
|
//#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
|
||||||
#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
|
//#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
|
||||||
|
|
||||||
//#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/
|
//#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/
|
||||||
#define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again
|
#define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again
|
||||||
|
@ -290,13 +350,12 @@
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// If you are using a RAMPS board or cheap E-bay purchased boards that do not detect when an SD card is inserted
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
// You can get round this by connecting a push button or single throw switch to the pin defined as SD_DETECT_PIN
|
// around this by connecting a push button or single throw switch to the pin defined
|
||||||
// in the pins.h file. When using a push button pulling the pin to ground this will need inverted. This setting should
|
// as SD_DETECT_PIN in your board's pins definitions.
|
||||||
// be commented out otherwise
|
// This setting should be disabled unless you are using a push button, pulling the pin to ground.
|
||||||
#ifndef ELB_FULL_GRAPHIC_CONTROLLER
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
#endif
|
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
||||||
#define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
|
#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 +404,13 @@
|
||||||
// @section more
|
// @section more
|
||||||
|
|
||||||
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
||||||
//#define USE_WATCHDOG
|
#define USE_WATCHDOG
|
||||||
|
|
||||||
#if ENABLED(USE_WATCHDOG)
|
#if ENABLED(USE_WATCHDOG)
|
||||||
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
||||||
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
||||||
// 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.
|
// 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.
|
||||||
//#define WATCHDOG_RESET_MANUAL
|
//#define WATCHDOG_RESET_MANUAL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
@ -362,6 +421,7 @@
|
||||||
//#define BABYSTEPPING
|
//#define BABYSTEPPING
|
||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
||||||
|
//not implemented for deltabots!
|
||||||
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
||||||
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
||||||
#endif
|
#endif
|
||||||
|
@ -380,7 +440,6 @@
|
||||||
#if ENABLED(ADVANCE)
|
#if ENABLED(ADVANCE)
|
||||||
#define EXTRUDER_ADVANCE_K .0
|
#define EXTRUDER_ADVANCE_K .0
|
||||||
#define D_FILAMENT 1.75
|
#define D_FILAMENT 1.75
|
||||||
#define STEPS_MM_E 836
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
@ -389,7 +448,7 @@
|
||||||
#define MM_PER_ARC_SEGMENT 1
|
#define MM_PER_ARC_SEGMENT 1
|
||||||
#define N_ARC_CORRECTION 25
|
#define N_ARC_CORRECTION 25
|
||||||
|
|
||||||
const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
|
@ -414,7 +473,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
|
|
||||||
//The ASCII buffer for receiving from the serial:
|
//The ASCII buffer for receiving from the serial:
|
||||||
#define MAX_CMD_SIZE 96
|
#define MAX_CMD_SIZE 96
|
||||||
#define BUFSIZE 4
|
#define BUFSIZE 8
|
||||||
|
|
||||||
// Bad Serial-connections can miss a received command by sending an 'ok'
|
// Bad Serial-connections can miss a received command by sending an 'ok'
|
||||||
// Therefore some clients abort after 30 seconds in a timeout.
|
// Therefore some clients abort after 30 seconds in a timeout.
|
||||||
|
@ -462,7 +521,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have TMC26X motor drivers.
|
* enable this section if you have TMC26X motor drivers.
|
||||||
* you need to import the TMC26XStepper library into the arduino IDE for this
|
* you need to import the TMC26XStepper library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section tmc
|
// @section tmc
|
||||||
|
@ -470,52 +529,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_TMCDRIVER
|
//#define HAVE_TMCDRIVER
|
||||||
#if ENABLED(HAVE_TMCDRIVER)
|
#if ENABLED(HAVE_TMCDRIVER)
|
||||||
|
|
||||||
//#define X_IS_TMC
|
//#define X_IS_TMC
|
||||||
#define X_MAX_CURRENT 1000 //in mA
|
#define X_MAX_CURRENT 1000 //in mA
|
||||||
#define X_SENSE_RESISTOR 91 //in mOhms
|
#define X_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define X2_IS_TMC
|
//#define X2_IS_TMC
|
||||||
#define X2_MAX_CURRENT 1000 //in mA
|
#define X2_MAX_CURRENT 1000 //in mA
|
||||||
#define X2_SENSE_RESISTOR 91 //in mOhms
|
#define X2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y_IS_TMC
|
//#define Y_IS_TMC
|
||||||
#define Y_MAX_CURRENT 1000 //in mA
|
#define Y_MAX_CURRENT 1000 //in mA
|
||||||
#define Y_SENSE_RESISTOR 91 //in mOhms
|
#define Y_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y2_IS_TMC
|
//#define Y2_IS_TMC
|
||||||
#define Y2_MAX_CURRENT 1000 //in mA
|
#define Y2_MAX_CURRENT 1000 //in mA
|
||||||
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z_IS_TMC
|
//#define Z_IS_TMC
|
||||||
#define Z_MAX_CURRENT 1000 //in mA
|
#define Z_MAX_CURRENT 1000 //in mA
|
||||||
#define Z_SENSE_RESISTOR 91 //in mOhms
|
#define Z_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z2_IS_TMC
|
//#define Z2_IS_TMC
|
||||||
#define Z2_MAX_CURRENT 1000 //in mA
|
#define Z2_MAX_CURRENT 1000 //in mA
|
||||||
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E0_IS_TMC
|
//#define E0_IS_TMC
|
||||||
#define E0_MAX_CURRENT 1000 //in mA
|
#define E0_MAX_CURRENT 1000 //in mA
|
||||||
#define E0_SENSE_RESISTOR 91 //in mOhms
|
#define E0_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E1_IS_TMC
|
//#define E1_IS_TMC
|
||||||
#define E1_MAX_CURRENT 1000 //in mA
|
#define E1_MAX_CURRENT 1000 //in mA
|
||||||
#define E1_SENSE_RESISTOR 91 //in mOhms
|
#define E1_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E2_IS_TMC
|
//#define E2_IS_TMC
|
||||||
#define E2_MAX_CURRENT 1000 //in mA
|
#define E2_MAX_CURRENT 1000 //in mA
|
||||||
#define E2_SENSE_RESISTOR 91 //in mOhms
|
#define E2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E3_IS_TMC
|
//#define E3_IS_TMC
|
||||||
#define E3_MAX_CURRENT 1000 //in mA
|
#define E3_MAX_CURRENT 1000 //in mA
|
||||||
#define E3_SENSE_RESISTOR 91 //in mOhms
|
#define E3_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
|
@ -524,7 +583,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have L6470 motor drivers.
|
* enable this section if you have L6470 motor drivers.
|
||||||
* you need to import the L6470 library into the arduino IDE for this
|
* you need to import the L6470 library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section l6470
|
// @section l6470
|
||||||
|
@ -532,63 +591,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_L6470DRIVER
|
//#define HAVE_L6470DRIVER
|
||||||
#if ENABLED(HAVE_L6470DRIVER)
|
#if ENABLED(HAVE_L6470DRIVER)
|
||||||
|
|
||||||
//#define X_IS_L6470
|
//#define X_IS_L6470
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define X2_IS_L6470
|
//#define X2_IS_L6470
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y_IS_L6470
|
//#define Y_IS_L6470
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y2_IS_L6470
|
//#define Y2_IS_L6470
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z_IS_L6470
|
//#define Z_IS_L6470
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z2_IS_L6470
|
//#define Z2_IS_L6470
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E0_IS_L6470
|
//#define E0_IS_L6470
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E1_IS_L6470
|
//#define E1_IS_L6470
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E2_IS_L6470
|
//#define E2_IS_L6470
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E3_IS_L6470
|
//#define E3_IS_L6470
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,40 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -7,8 +44,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -16,11 +55,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -95,7 +130,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// The following define selects which electronics board you have.
|
// The following define selects which electronics board you have.
|
||||||
// Please choose the name from boards.h that matches your setup
|
// Please choose the name from boards.h that matches your setup
|
||||||
#ifndef MOTHERBOARD
|
#ifndef MOTHERBOARD
|
||||||
#define MOTHERBOARD BOARD_RAMPS_13_EFB
|
#define MOTHERBOARD BOARD_RAMPS_14_EFB
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Optional custom name for your RepStrap or other custom machine
|
// Optional custom name for your RepStrap or other custom machine
|
||||||
|
@ -135,6 +170,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -154,6 +190,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -169,7 +206,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 1
|
#define TEMP_SENSOR_0 1
|
||||||
#define TEMP_SENSOR_1 0
|
#define TEMP_SENSOR_1 0
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
|
@ -203,14 +240,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define HEATER_3_MAXTEMP 275
|
#define HEATER_3_MAXTEMP 275
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
#define EXTRUDER_WATTS (2*2/5.9) // P=I^2/R
|
#define EXTRUDER_WATTS (2*2/5.9) // P=U^2/R
|
||||||
#define BED_WATTS (5.45*5.45/2.2) // P=I^2/R
|
#define BED_WATTS (5.45*5.45/2.2) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -222,6 +254,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
|
@ -253,7 +286,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// If this is enabled, find your own PID constants below.
|
// If this is enabled, find your own PID constants below.
|
||||||
#define PIDTEMPBED
|
#define PIDTEMPBED
|
||||||
|
|
||||||
#define BED_LIMIT_SWITCHING
|
//#define BED_LIMIT_SWITCHING
|
||||||
|
|
||||||
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||||
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||||
|
@ -261,10 +294,10 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
|
|
||||||
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
||||||
|
|
||||||
//12v Heatbed Mk3 12V in parallel
|
//12v Heatbed Mk3 12V in parallel
|
||||||
|
@ -292,16 +325,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -322,8 +354,22 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
#define USE_XMIN_PLUG
|
||||||
|
#define USE_YMIN_PLUG
|
||||||
|
//#define USE_ZMIN_PLUG
|
||||||
|
//#define USE_XMAX_PLUG
|
||||||
|
//#define USE_YMAX_PLUG
|
||||||
|
#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
//#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
//#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -331,9 +377,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
|
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
|
||||||
//#define ENDSTOPPULLUP_XMAX
|
//#define ENDSTOPPULLUP_XMAX
|
||||||
//#define ENDSTOPPULLUP_YMAX
|
//#define ENDSTOPPULLUP_YMAX
|
||||||
#define ENDSTOPPULLUP_ZMAX // open pin, inverted
|
#define ENDSTOPPULLUP_ZMAX // open pin, inverted
|
||||||
#define ENDSTOPPULLUP_XMIN // open pin, inverted
|
#define ENDSTOPPULLUP_XMIN // open pin, inverted
|
||||||
#define ENDSTOPPULLUP_YMIN // open pin, inverted
|
#define ENDSTOPPULLUP_YMIN // open pin, inverted
|
||||||
//#define ENDSTOPPULLUP_ZMIN
|
//#define ENDSTOPPULLUP_ZMIN
|
||||||
//#define ENDSTOPPULLUP_ZMIN_PROBE
|
//#define ENDSTOPPULLUP_ZMIN_PROBE
|
||||||
#endif
|
#endif
|
||||||
|
@ -346,13 +392,53 @@ const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
//#define DISABLE_MAX_ENDSTOPS
|
|
||||||
//#define DISABLE_MIN_ENDSTOPS
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -362,11 +448,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z false
|
#define DISABLE_Z false
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -389,6 +477,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define INVERT_E3_DIR false
|
#define INVERT_E3_DIR false
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
@ -424,24 +514,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
|
||||||
#define MESH_MIN_Y 10
|
#define MESH_MIN_Y 10
|
||||||
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
|
#define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -452,7 +544,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
//#define DEBUG_LEVELING_FEATURE
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
//#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
//#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
|
@ -464,7 +556,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -478,7 +570,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define FRONT_PROBE_BED_POSITION 20
|
#define FRONT_PROBE_BED_POSITION 20
|
||||||
#define BACK_PROBE_BED_POSITION 170
|
#define BACK_PROBE_BED_POSITION 170
|
||||||
|
|
||||||
#define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
|
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
|
||||||
|
|
||||||
// Set the number of grid points per dimension.
|
// Set the number of grid points per dimension.
|
||||||
// You probably don't need more than 3 (squared=9).
|
// You probably don't need more than 3 (squared=9).
|
||||||
|
@ -486,25 +578,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X 15
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y 180
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X 15
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y 20
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X 170
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
//#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
|
@ -512,21 +616,34 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
||||||
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
//#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
//#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
//#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
// When defined, it will:
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// When defined, it will:
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - Position the Z probe in a defined XY point before Z Homing when homing all axis (G28).
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
// - Block Z homing only when the Z probe is outside bed area.
|
// - Position the Z probe in a defined XY point before Z Homing when homing all axis (G28).
|
||||||
|
// - Block Z homing only when the Z probe is outside bed area.
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
|
|
||||||
|
@ -535,37 +652,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
|
||||||
|
@ -639,6 +725,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -659,13 +753,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
@ -673,12 +767,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
//#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)
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
|
||||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
||||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
|
@ -695,13 +789,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -716,7 +810,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
@ -739,6 +833,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -752,7 +848,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
// SSD1306 OLED generic display support
|
// SSD1306 OLED generic display support
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define U8GLIB_SSD1306
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
|
@ -764,7 +860,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
//#define FAST_PWM_FAN
|
//#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
@ -844,21 +940,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#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
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
|
|
||||||
//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.
|
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
|
@ -1,3 +1,35 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration_adv.h
|
||||||
|
*
|
||||||
|
* Advanced settings.
|
||||||
|
* Only change these if you know exactly what you're doing.
|
||||||
|
* Some of these settings can damage your printer if improperly set!
|
||||||
|
*
|
||||||
|
* Basic settings can be found in Configuration.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
|
|
||||||
|
@ -9,13 +41,26 @@
|
||||||
//=============================Thermal Settings ============================
|
//=============================Thermal Settings ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
#if DISABLED(PIDTEMPBED)
|
||||||
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
#define BED_CHECK_INTERVAL 3000 // ms between checks in bang-bang control
|
||||||
|
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||||
|
#define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#define BED_CHECK_INTERVAL 3000 //ms between checks in bang-bang control
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection parameters
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
|
*
|
||||||
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
|
*
|
||||||
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
|
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
||||||
|
* the firmware will halt the machine as a safety precaution.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
|
||||||
*/
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
||||||
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
||||||
|
@ -26,26 +71,24 @@
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* but only if the current temperature is far enough below the target for a reliable test.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
|
||||||
|
* WATCH_TEMP_INCREASE should not be below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 16 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 4 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Thermal Protection parameters for the bed
|
||||||
|
* are like the above for the hotends.
|
||||||
|
* WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
|
||||||
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_BED)
|
#if ENABLED(THERMAL_PROTECTION_BED)
|
||||||
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
|
||||||
* Automatic Temperature:
|
|
||||||
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
|
||||||
* The maximum buffered steps/sec of the extruder motor is called "se".
|
|
||||||
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
|
||||||
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
|
||||||
* mintemp and maxtemp. Turn this off by excuting M109 without F*
|
|
||||||
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
|
||||||
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
|
||||||
*/
|
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||||
|
@ -56,14 +99,16 @@
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
|
* Automatic Temperature:
|
||||||
//The maximum buffered steps/sec of the extruder motor are called "se".
|
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
||||||
//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
|
* The maximum buffered steps/sec of the extruder motor is called "se".
|
||||||
// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
|
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
||||||
// you exit the value by any M109 without F*
|
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
||||||
// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
|
* mintemp and maxtemp. Turn this off by executing M109 without F*
|
||||||
// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
||||||
|
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
||||||
|
*/
|
||||||
#define AUTOTEMP
|
#define AUTOTEMP
|
||||||
#if ENABLED(AUTOTEMP)
|
#if ENABLED(AUTOTEMP)
|
||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
|
@ -156,9 +201,7 @@
|
||||||
//#define Z_DUAL_ENDSTOPS
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_MAX_PIN 36 //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36)
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
const bool Z2_MAX_ENDSTOP_INVERTING = false;
|
|
||||||
#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.
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
#endif // Z_DUAL_STEPPER_DRIVERS
|
||||||
|
@ -240,7 +283,13 @@
|
||||||
#define INVERT_E_STEP_PIN false
|
#define INVERT_E_STEP_PIN false
|
||||||
|
|
||||||
// Default stepper release if idle. Set to 0 to deactivate.
|
// Default stepper release if idle. Set to 0 to deactivate.
|
||||||
|
// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
|
||||||
|
// Time can be set by M18 and M84.
|
||||||
#define DEFAULT_STEPPER_DEACTIVE_TIME 240
|
#define DEFAULT_STEPPER_DEACTIVE_TIME 240
|
||||||
|
#define DISABLE_INACTIVE_X true
|
||||||
|
#define DISABLE_INACTIVE_Y true
|
||||||
|
#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished.
|
||||||
|
#define DISABLE_INACTIVE_E true
|
||||||
|
|
||||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
||||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
||||||
|
@ -276,6 +325,9 @@
|
||||||
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
||||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||||
|
|
||||||
|
// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
|
||||||
|
//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
|
||||||
|
|
||||||
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
||||||
|
@ -349,17 +401,16 @@
|
||||||
//#define USE_SMALL_INFOFONT
|
//#define USE_SMALL_INFOFONT
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
|
|
||||||
// @section more
|
// @section more
|
||||||
|
|
||||||
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
||||||
//#define USE_WATCHDOG
|
#define USE_WATCHDOG
|
||||||
|
|
||||||
#if ENABLED(USE_WATCHDOG)
|
#if ENABLED(USE_WATCHDOG)
|
||||||
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
||||||
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
||||||
// 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.
|
// 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.
|
||||||
//#define WATCHDOG_RESET_MANUAL
|
//#define WATCHDOG_RESET_MANUAL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
@ -370,6 +421,7 @@
|
||||||
//#define BABYSTEPPING
|
//#define BABYSTEPPING
|
||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
||||||
|
//not implemented for deltabots!
|
||||||
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
||||||
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
||||||
#endif
|
#endif
|
||||||
|
@ -388,7 +440,6 @@
|
||||||
#if ENABLED(ADVANCE)
|
#if ENABLED(ADVANCE)
|
||||||
#define EXTRUDER_ADVANCE_K .0
|
#define EXTRUDER_ADVANCE_K .0
|
||||||
#define D_FILAMENT 1.75
|
#define D_FILAMENT 1.75
|
||||||
#define STEPS_MM_E 1000
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
@ -397,7 +448,7 @@
|
||||||
#define MM_PER_ARC_SEGMENT 1
|
#define MM_PER_ARC_SEGMENT 1
|
||||||
#define N_ARC_CORRECTION 25
|
#define N_ARC_CORRECTION 25
|
||||||
|
|
||||||
const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
|
@ -462,12 +513,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
#define FILAMENTCHANGE_ZADD 10
|
#define FILAMENTCHANGE_ZADD 10
|
||||||
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||||
#define FILAMENTCHANGE_FINALRETRACT -100
|
#define FILAMENTCHANGE_FINALRETRACT -100
|
||||||
|
#define AUTO_FILAMENT_CHANGE //This extrude filament until you press the button on LCD
|
||||||
|
#define AUTO_FILAMENT_CHANGE_LENGTH 0.04 //Extrusion length on automatic extrusion loop
|
||||||
|
#define AUTO_FILAMENT_CHANGE_FEEDRATE 300 //Extrusion feedrate (mm/min) on automatic extrusion loop
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have TMC26X motor drivers.
|
* enable this section if you have TMC26X motor drivers.
|
||||||
* you need to import the TMC26XStepper library into the arduino IDE for this
|
* you need to import the TMC26XStepper library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section tmc
|
// @section tmc
|
||||||
|
@ -475,52 +529,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_TMCDRIVER
|
//#define HAVE_TMCDRIVER
|
||||||
#if ENABLED(HAVE_TMCDRIVER)
|
#if ENABLED(HAVE_TMCDRIVER)
|
||||||
|
|
||||||
//#define X_IS_TMC
|
//#define X_IS_TMC
|
||||||
#define X_MAX_CURRENT 1000 //in mA
|
#define X_MAX_CURRENT 1000 //in mA
|
||||||
#define X_SENSE_RESISTOR 91 //in mOhms
|
#define X_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define X2_IS_TMC
|
//#define X2_IS_TMC
|
||||||
#define X2_MAX_CURRENT 1000 //in mA
|
#define X2_MAX_CURRENT 1000 //in mA
|
||||||
#define X2_SENSE_RESISTOR 91 //in mOhms
|
#define X2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y_IS_TMC
|
//#define Y_IS_TMC
|
||||||
#define Y_MAX_CURRENT 1000 //in mA
|
#define Y_MAX_CURRENT 1000 //in mA
|
||||||
#define Y_SENSE_RESISTOR 91 //in mOhms
|
#define Y_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y2_IS_TMC
|
//#define Y2_IS_TMC
|
||||||
#define Y2_MAX_CURRENT 1000 //in mA
|
#define Y2_MAX_CURRENT 1000 //in mA
|
||||||
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z_IS_TMC
|
//#define Z_IS_TMC
|
||||||
#define Z_MAX_CURRENT 1000 //in mA
|
#define Z_MAX_CURRENT 1000 //in mA
|
||||||
#define Z_SENSE_RESISTOR 91 //in mOhms
|
#define Z_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z2_IS_TMC
|
//#define Z2_IS_TMC
|
||||||
#define Z2_MAX_CURRENT 1000 //in mA
|
#define Z2_MAX_CURRENT 1000 //in mA
|
||||||
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E0_IS_TMC
|
//#define E0_IS_TMC
|
||||||
#define E0_MAX_CURRENT 1000 //in mA
|
#define E0_MAX_CURRENT 1000 //in mA
|
||||||
#define E0_SENSE_RESISTOR 91 //in mOhms
|
#define E0_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E1_IS_TMC
|
//#define E1_IS_TMC
|
||||||
#define E1_MAX_CURRENT 1000 //in mA
|
#define E1_MAX_CURRENT 1000 //in mA
|
||||||
#define E1_SENSE_RESISTOR 91 //in mOhms
|
#define E1_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E2_IS_TMC
|
//#define E2_IS_TMC
|
||||||
#define E2_MAX_CURRENT 1000 //in mA
|
#define E2_MAX_CURRENT 1000 //in mA
|
||||||
#define E2_SENSE_RESISTOR 91 //in mOhms
|
#define E2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E3_IS_TMC
|
//#define E3_IS_TMC
|
||||||
#define E3_MAX_CURRENT 1000 //in mA
|
#define E3_MAX_CURRENT 1000 //in mA
|
||||||
#define E3_SENSE_RESISTOR 91 //in mOhms
|
#define E3_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
|
@ -529,7 +583,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have L6470 motor drivers.
|
* enable this section if you have L6470 motor drivers.
|
||||||
* you need to import the L6470 library into the arduino IDE for this
|
* you need to import the L6470 library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section l6470
|
// @section l6470
|
||||||
|
@ -537,63 +591,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_L6470DRIVER
|
//#define HAVE_L6470DRIVER
|
||||||
#if ENABLED(HAVE_L6470DRIVER)
|
#if ENABLED(HAVE_L6470DRIVER)
|
||||||
|
|
||||||
//#define X_IS_L6470
|
//#define X_IS_L6470
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define X2_IS_L6470
|
//#define X2_IS_L6470
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y_IS_L6470
|
//#define Y_IS_L6470
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y2_IS_L6470
|
//#define Y2_IS_L6470
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z_IS_L6470
|
//#define Z_IS_L6470
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z2_IS_L6470
|
//#define Z2_IS_L6470
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E0_IS_L6470
|
//#define E0_IS_L6470
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E1_IS_L6470
|
//#define E1_IS_L6470
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E2_IS_L6470
|
//#define E2_IS_L6470
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E3_IS_L6470
|
//#define E3_IS_L6470
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,40 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -7,8 +44,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -16,11 +55,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -110,6 +145,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -129,6 +165,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -144,7 +181,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 7
|
#define TEMP_SENSOR_0 7
|
||||||
#define TEMP_SENSOR_1 7
|
#define TEMP_SENSOR_1 7
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
|
@ -178,14 +215,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define HEATER_3_MAXTEMP 250
|
#define HEATER_3_MAXTEMP 250
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
|
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
|
||||||
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
|
//#define BED_WATTS (12.0*12.0/1.1) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -197,6 +229,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 70 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 70 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX 74 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX 74 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
|
@ -207,7 +240,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
|
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
|
||||||
#define K1 0.95 //smoothing factor within the PID
|
#define K1 0.95 //smoothing factor within the PID
|
||||||
|
|
||||||
// If you are using a preconfigured hotend then you can use one of the value sets by uncommenting it
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
// Buda 2.0 on 24V
|
// Buda 2.0 on 24V
|
||||||
#define DEFAULT_Kp 6
|
#define DEFAULT_Kp 6
|
||||||
#define DEFAULT_Ki .3
|
#define DEFAULT_Ki .3
|
||||||
|
@ -257,9 +290,10 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
#define MAX_BED_POWER 206 // limits duty cycle to bed; 255=full current
|
#define MAX_BED_POWER 206 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
|
|
||||||
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
||||||
|
|
||||||
//24V 360W silicone heater from NPH on 3mm borosilicate (TAZ 2.2+)
|
//24V 360W silicone heater from NPH on 3mm borosilicate (TAZ 2.2+)
|
||||||
|
@ -273,13 +307,13 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//#define DEFAULT_bedKi 60
|
//#define DEFAULT_bedKi 60
|
||||||
//#define DEFAULT_bedKd 1800
|
//#define DEFAULT_bedKd 1800
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||||
//#define DEFAULT_bedKp 10.00
|
//#define DEFAULT_bedKp 10.00
|
||||||
//#define DEFAULT_bedKi .023
|
//#define DEFAULT_bedKi .023
|
||||||
//#define DEFAULT_bedKd 305.4
|
//#define DEFAULT_bedKd 305.4
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from pidautotune
|
//from pidautotune
|
||||||
//#define DEFAULT_bedKp 97.1
|
//#define DEFAULT_bedKp 97.1
|
||||||
//#define DEFAULT_bedKi 1.41
|
//#define DEFAULT_bedKi 1.41
|
||||||
|
@ -304,16 +338,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -334,8 +367,22 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
#define USE_XMIN_PLUG
|
||||||
|
#define USE_YMIN_PLUG
|
||||||
|
#define USE_ZMIN_PLUG
|
||||||
|
//#define USE_XMAX_PLUG
|
||||||
|
//#define USE_YMAX_PLUG
|
||||||
|
//#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -358,13 +405,53 @@ const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
#define DISABLE_MAX_ENDSTOPS
|
|
||||||
//#define DISABLE_MIN_ENDSTOPS
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -374,11 +461,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z false
|
#define DISABLE_Z false
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -401,6 +490,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define INVERT_E3_DIR true
|
#define INVERT_E3_DIR true
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
@ -436,24 +527,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
|
||||||
#define MESH_MIN_Y 10
|
#define MESH_MIN_Y 10
|
||||||
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
|
#define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -462,10 +555,11 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section bedlevel
|
// @section bedlevel
|
||||||
|
|
||||||
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line).
|
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z probe repeatability test will be included if auto bed leveling is enabled.
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
|
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
// There are 2 different ways to specify probing locations:
|
// There are 2 different ways to specify probing locations:
|
||||||
//
|
//
|
||||||
|
@ -475,7 +569,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -497,25 +591,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X 15
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y 180
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X 15
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y 20
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X 170
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
|
@ -523,16 +629,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
||||||
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
//#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
|
@ -546,38 +665,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // ENABLE_AUTO_BED_LEVELING
|
|
||||||
|
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
@ -628,7 +716,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// Custom M code points
|
// Custom M code points
|
||||||
#define CUSTOM_M_CODES
|
#define CUSTOM_M_CODES
|
||||||
#if ENABLED(CUSTOM_M_CODES)
|
#if ENABLED(CUSTOM_M_CODES)
|
||||||
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
#define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
|
#define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
|
||||||
#define Z_PROBE_OFFSET_RANGE_MIN -20
|
#define Z_PROBE_OFFSET_RANGE_MIN -20
|
||||||
#define Z_PROBE_OFFSET_RANGE_MAX 20
|
#define Z_PROBE_OFFSET_RANGE_MAX 20
|
||||||
|
@ -650,6 +738,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -670,13 +766,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
@ -684,12 +780,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
//#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)
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
|
||||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
#define ENCODER_PULSES_PER_STEP 2 // Increase if you have a high resolution encoder
|
#define ENCODER_PULSES_PER_STEP 2 // Increase if you have a high resolution encoder
|
||||||
#define ENCODER_STEPS_PER_MENU_ITEM 1 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
#define ENCODER_STEPS_PER_MENU_ITEM 1 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
|
@ -706,13 +802,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -727,7 +823,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
@ -750,6 +846,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -763,7 +861,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
// SSD1306 OLED generic display support
|
// SSD1306 OLED generic display support
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define U8GLIB_SSD1306
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
|
@ -775,7 +873,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
#define FAST_PWM_FAN
|
#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
@ -855,21 +953,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#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
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
|
|
||||||
//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.
|
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
|
@ -1,3 +1,35 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration_adv.h
|
||||||
|
*
|
||||||
|
* Advanced settings.
|
||||||
|
* Only change these if you know exactly what you're doing.
|
||||||
|
* Some of these settings can damage your printer if improperly set!
|
||||||
|
*
|
||||||
|
* Basic settings can be found in Configuration.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
|
|
||||||
|
@ -9,13 +41,26 @@
|
||||||
//=============================Thermal Settings ============================
|
//=============================Thermal Settings ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
#if DISABLED(PIDTEMPBED)
|
||||||
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||||
|
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||||
|
#define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection parameters
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
|
*
|
||||||
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
|
*
|
||||||
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
|
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
||||||
|
* the firmware will halt the machine as a safety precaution.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
|
||||||
*/
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
||||||
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
||||||
|
@ -26,11 +71,19 @@
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* but only if the current temperature is far enough below the target for a reliable test.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
|
||||||
|
* WATCH_TEMP_INCREASE should not be below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 16 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 4 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Thermal Protection parameters for the bed
|
||||||
|
* are like the above for the hotends.
|
||||||
|
* WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
|
||||||
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_BED)
|
#if ENABLED(THERMAL_PROTECTION_BED)
|
||||||
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
@ -52,7 +105,7 @@
|
||||||
* The maximum buffered steps/sec of the extruder motor is called "se".
|
* The maximum buffered steps/sec of the extruder motor is called "se".
|
||||||
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
||||||
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
||||||
* mintemp and maxtemp. Turn this off by excuting M109 without F*
|
* mintemp and maxtemp. Turn this off by executing M109 without F*
|
||||||
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
||||||
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
||||||
*/
|
*/
|
||||||
|
@ -156,9 +209,7 @@
|
||||||
//#define Z_DUAL_ENDSTOPS
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_MAX_PIN 36 //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36)
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
const bool Z2_MAX_ENDSTOP_INVERTING = false;
|
|
||||||
#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.
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
#endif // Z_DUAL_STEPPER_DRIVERS
|
||||||
|
@ -240,7 +291,13 @@
|
||||||
#define INVERT_E_STEP_PIN false
|
#define INVERT_E_STEP_PIN false
|
||||||
|
|
||||||
// Default stepper release if idle. Set to 0 to deactivate.
|
// Default stepper release if idle. Set to 0 to deactivate.
|
||||||
|
// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
|
||||||
|
// Time can be set by M18 and M84.
|
||||||
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
||||||
|
#define DISABLE_INACTIVE_X true
|
||||||
|
#define DISABLE_INACTIVE_Y true
|
||||||
|
#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished.
|
||||||
|
#define DISABLE_INACTIVE_E true
|
||||||
|
|
||||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
||||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
||||||
|
@ -276,6 +333,9 @@
|
||||||
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
||||||
#define DIGIPOT_MOTOR_CURRENT {175,175,240,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
#define DIGIPOT_MOTOR_CURRENT {175,175,240,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||||
|
|
||||||
|
// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
|
||||||
|
//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
|
||||||
|
|
||||||
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
||||||
|
@ -352,13 +412,13 @@
|
||||||
// @section more
|
// @section more
|
||||||
|
|
||||||
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
||||||
//#define USE_WATCHDOG
|
#define USE_WATCHDOG
|
||||||
|
|
||||||
#if ENABLED(USE_WATCHDOG)
|
#if ENABLED(USE_WATCHDOG)
|
||||||
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
||||||
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
||||||
// 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.
|
// 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.
|
||||||
//#define WATCHDOG_RESET_MANUAL
|
//#define WATCHDOG_RESET_MANUAL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
@ -369,7 +429,7 @@
|
||||||
//#define BABYSTEPPING
|
//#define BABYSTEPPING
|
||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
||||||
//not implemented for CoreXY and deltabots!
|
//not implemented for deltabots!
|
||||||
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
||||||
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
||||||
#endif
|
#endif
|
||||||
|
@ -388,7 +448,6 @@
|
||||||
#if ENABLED(ADVANCE)
|
#if ENABLED(ADVANCE)
|
||||||
#define EXTRUDER_ADVANCE_K .0
|
#define EXTRUDER_ADVANCE_K .0
|
||||||
#define D_FILAMENT 2.85
|
#define D_FILAMENT 2.85
|
||||||
#define STEPS_MM_E 836
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
@ -397,7 +456,7 @@
|
||||||
#define MM_PER_ARC_SEGMENT 1
|
#define MM_PER_ARC_SEGMENT 1
|
||||||
#define N_ARC_CORRECTION 25
|
#define N_ARC_CORRECTION 25
|
||||||
|
|
||||||
const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
|
@ -470,7 +529,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have TMC26X motor drivers.
|
* enable this section if you have TMC26X motor drivers.
|
||||||
* you need to import the TMC26XStepper library into the arduino IDE for this
|
* you need to import the TMC26XStepper library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section tmc
|
// @section tmc
|
||||||
|
@ -478,52 +537,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_TMCDRIVER
|
//#define HAVE_TMCDRIVER
|
||||||
#if ENABLED(HAVE_TMCDRIVER)
|
#if ENABLED(HAVE_TMCDRIVER)
|
||||||
|
|
||||||
//#define X_IS_TMC
|
//#define X_IS_TMC
|
||||||
#define X_MAX_CURRENT 1000 //in mA
|
#define X_MAX_CURRENT 1000 //in mA
|
||||||
#define X_SENSE_RESISTOR 91 //in mOhms
|
#define X_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define X2_IS_TMC
|
//#define X2_IS_TMC
|
||||||
#define X2_MAX_CURRENT 1000 //in mA
|
#define X2_MAX_CURRENT 1000 //in mA
|
||||||
#define X2_SENSE_RESISTOR 91 //in mOhms
|
#define X2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y_IS_TMC
|
//#define Y_IS_TMC
|
||||||
#define Y_MAX_CURRENT 1000 //in mA
|
#define Y_MAX_CURRENT 1000 //in mA
|
||||||
#define Y_SENSE_RESISTOR 91 //in mOhms
|
#define Y_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y2_IS_TMC
|
//#define Y2_IS_TMC
|
||||||
#define Y2_MAX_CURRENT 1000 //in mA
|
#define Y2_MAX_CURRENT 1000 //in mA
|
||||||
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z_IS_TMC
|
//#define Z_IS_TMC
|
||||||
#define Z_MAX_CURRENT 1000 //in mA
|
#define Z_MAX_CURRENT 1000 //in mA
|
||||||
#define Z_SENSE_RESISTOR 91 //in mOhms
|
#define Z_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z2_IS_TMC
|
//#define Z2_IS_TMC
|
||||||
#define Z2_MAX_CURRENT 1000 //in mA
|
#define Z2_MAX_CURRENT 1000 //in mA
|
||||||
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E0_IS_TMC
|
//#define E0_IS_TMC
|
||||||
#define E0_MAX_CURRENT 1000 //in mA
|
#define E0_MAX_CURRENT 1000 //in mA
|
||||||
#define E0_SENSE_RESISTOR 91 //in mOhms
|
#define E0_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E1_IS_TMC
|
//#define E1_IS_TMC
|
||||||
#define E1_MAX_CURRENT 1000 //in mA
|
#define E1_MAX_CURRENT 1000 //in mA
|
||||||
#define E1_SENSE_RESISTOR 91 //in mOhms
|
#define E1_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E2_IS_TMC
|
//#define E2_IS_TMC
|
||||||
#define E2_MAX_CURRENT 1000 //in mA
|
#define E2_MAX_CURRENT 1000 //in mA
|
||||||
#define E2_SENSE_RESISTOR 91 //in mOhms
|
#define E2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E3_IS_TMC
|
//#define E3_IS_TMC
|
||||||
#define E3_MAX_CURRENT 1000 //in mA
|
#define E3_MAX_CURRENT 1000 //in mA
|
||||||
#define E3_SENSE_RESISTOR 91 //in mOhms
|
#define E3_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
|
@ -532,7 +591,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have L6470 motor drivers.
|
* enable this section if you have L6470 motor drivers.
|
||||||
* you need to import the L6470 library into the arduino IDE for this
|
* you need to import the L6470 library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section l6470
|
// @section l6470
|
||||||
|
@ -540,63 +599,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_L6470DRIVER
|
//#define HAVE_L6470DRIVER
|
||||||
#if ENABLED(HAVE_L6470DRIVER)
|
#if ENABLED(HAVE_L6470DRIVER)
|
||||||
|
|
||||||
//#define X_IS_L6470
|
//#define X_IS_L6470
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define X2_IS_L6470
|
//#define X2_IS_L6470
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y_IS_L6470
|
//#define Y_IS_L6470
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y2_IS_L6470
|
//#define Y2_IS_L6470
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z_IS_L6470
|
//#define Z_IS_L6470
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z2_IS_L6470
|
//#define Z2_IS_L6470
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E0_IS_L6470
|
//#define E0_IS_L6470
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E1_IS_L6470
|
//#define E1_IS_L6470
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E2_IS_L6470
|
//#define E2_IS_L6470
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E3_IS_L6470
|
//#define E3_IS_L6470
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,40 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -7,8 +44,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -16,11 +55,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -70,7 +105,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// The following define selects which electronics board you have.
|
// The following define selects which electronics board you have.
|
||||||
// Please choose the name from boards.h that matches your setup
|
// Please choose the name from boards.h that matches your setup
|
||||||
#ifndef MOTHERBOARD
|
#ifndef MOTHERBOARD
|
||||||
#define MOTHERBOARD BOARD_RAMPS_13_EFB
|
#define MOTHERBOARD BOARD_RAMPS_14_EFB
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Optional custom name for your RepStrap or other custom machine
|
// Optional custom name for your RepStrap or other custom machine
|
||||||
|
@ -113,6 +148,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -132,6 +168,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -147,7 +184,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 1
|
#define TEMP_SENSOR_0 1
|
||||||
#define TEMP_SENSOR_1 0
|
#define TEMP_SENSOR_1 0
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
|
@ -181,14 +218,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define HEATER_3_MAXTEMP 260
|
#define HEATER_3_MAXTEMP 260
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
|
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
|
||||||
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
|
//#define BED_WATTS (12.0*12.0/1.1) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -200,6 +232,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
|
@ -239,19 +272,19 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
|
|
||||||
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||||
#define DEFAULT_bedKp 10.00
|
#define DEFAULT_bedKp 10.00
|
||||||
#define DEFAULT_bedKi .023
|
#define DEFAULT_bedKi .023
|
||||||
#define DEFAULT_bedKd 305.4
|
#define DEFAULT_bedKd 305.4
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from pidautotune
|
//from pidautotune
|
||||||
//#define DEFAULT_bedKp 97.1
|
//#define DEFAULT_bedKp 97.1
|
||||||
//#define DEFAULT_bedKi 1.41
|
//#define DEFAULT_bedKi 1.41
|
||||||
|
@ -276,16 +309,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -306,8 +338,22 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
#define USE_XMIN_PLUG
|
||||||
|
#define USE_YMIN_PLUG
|
||||||
|
#define USE_ZMIN_PLUG
|
||||||
|
//#define USE_XMAX_PLUG
|
||||||
|
//#define USE_YMAX_PLUG
|
||||||
|
//#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -330,13 +376,53 @@ const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
//#define DISABLE_MAX_ENDSTOPS
|
|
||||||
//#define DISABLE_MIN_ENDSTOPS
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -346,11 +432,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z true
|
#define DISABLE_Z true
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -373,6 +461,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define INVERT_E3_DIR false
|
#define INVERT_E3_DIR false
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
@ -408,24 +498,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
|
||||||
#define MESH_MIN_Y 10
|
#define MESH_MIN_Y 10
|
||||||
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
|
#define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -436,7 +528,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
//#define DEBUG_LEVELING_FEATURE
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
|
@ -448,7 +540,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -462,7 +554,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define FRONT_PROBE_BED_POSITION 20
|
#define FRONT_PROBE_BED_POSITION 20
|
||||||
#define BACK_PROBE_BED_POSITION 170
|
#define BACK_PROBE_BED_POSITION 170
|
||||||
|
|
||||||
#define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
|
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
|
||||||
|
|
||||||
// Set the number of grid points per dimension.
|
// Set the number of grid points per dimension.
|
||||||
// You probably don't need more than 3 (squared=9).
|
// You probably don't need more than 3 (squared=9).
|
||||||
|
@ -470,25 +562,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X 15
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y 180
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X 15
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y 20
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X 170
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
|
@ -496,16 +600,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
||||||
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
//#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
|
@ -519,37 +636,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
|
||||||
|
@ -623,6 +709,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -643,13 +737,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
@ -657,11 +751,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define ULTRA_LCD //general LCD support, also 16x2
|
#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
//#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)
|
||||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
||||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
|
@ -678,13 +773,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -699,7 +794,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
@ -722,6 +817,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -735,7 +832,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
// SSD1306 OLED generic display support
|
// SSD1306 OLED generic display support
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define U8GLIB_SSD1306
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
|
@ -747,7 +844,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
//#define FAST_PWM_FAN
|
//#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
@ -827,21 +924,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#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
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
|
|
||||||
//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.
|
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
|
@ -1,3 +1,35 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration_adv.h
|
||||||
|
*
|
||||||
|
* Advanced settings.
|
||||||
|
* Only change these if you know exactly what you're doing.
|
||||||
|
* Some of these settings can damage your printer if improperly set!
|
||||||
|
*
|
||||||
|
* Basic settings can be found in Configuration.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
|
|
||||||
|
@ -9,13 +41,26 @@
|
||||||
//=============================Thermal Settings ============================
|
//=============================Thermal Settings ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
#if DISABLED(PIDTEMPBED)
|
||||||
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||||
|
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||||
|
#define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection parameters
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
|
*
|
||||||
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
|
*
|
||||||
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
|
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
||||||
|
* the firmware will halt the machine as a safety precaution.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
|
||||||
*/
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
||||||
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
||||||
|
@ -26,26 +71,24 @@
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* but only if the current temperature is far enough below the target for a reliable test.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
|
||||||
|
* WATCH_TEMP_INCREASE should not be below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 16 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 4 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Thermal Protection parameters for the bed
|
||||||
|
* are like the above for the hotends.
|
||||||
|
* WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
|
||||||
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_BED)
|
#if ENABLED(THERMAL_PROTECTION_BED)
|
||||||
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
|
||||||
* Automatic Temperature:
|
|
||||||
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
|
||||||
* The maximum buffered steps/sec of the extruder motor is called "se".
|
|
||||||
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
|
||||||
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
|
||||||
* mintemp and maxtemp. Turn this off by excuting M109 without F*
|
|
||||||
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
|
||||||
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
|
||||||
*/
|
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||||
|
@ -56,14 +99,16 @@
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
|
* Automatic Temperature:
|
||||||
//The maximum buffered steps/sec of the extruder motor are called "se".
|
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
||||||
//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
|
* The maximum buffered steps/sec of the extruder motor is called "se".
|
||||||
// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
|
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
||||||
// you exit the value by any M109 without F*
|
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
||||||
// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
|
* mintemp and maxtemp. Turn this off by executing M109 without F*
|
||||||
// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
||||||
|
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
||||||
|
*/
|
||||||
#define AUTOTEMP
|
#define AUTOTEMP
|
||||||
#if ENABLED(AUTOTEMP)
|
#if ENABLED(AUTOTEMP)
|
||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
|
@ -156,9 +201,7 @@
|
||||||
//#define Z_DUAL_ENDSTOPS
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_MAX_PIN 36 //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36)
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
const bool Z2_MAX_ENDSTOP_INVERTING = false;
|
|
||||||
#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.
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
#endif // Z_DUAL_STEPPER_DRIVERS
|
||||||
|
@ -240,7 +283,13 @@
|
||||||
#define INVERT_E_STEP_PIN false
|
#define INVERT_E_STEP_PIN false
|
||||||
|
|
||||||
// Default stepper release if idle. Set to 0 to deactivate.
|
// Default stepper release if idle. Set to 0 to deactivate.
|
||||||
|
// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
|
||||||
|
// Time can be set by M18 and M84.
|
||||||
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
||||||
|
#define DISABLE_INACTIVE_X true
|
||||||
|
#define DISABLE_INACTIVE_Y true
|
||||||
|
#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished.
|
||||||
|
#define DISABLE_INACTIVE_E true
|
||||||
|
|
||||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
||||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
||||||
|
@ -276,6 +325,9 @@
|
||||||
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
||||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||||
|
|
||||||
|
// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
|
||||||
|
//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
|
||||||
|
|
||||||
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
||||||
|
@ -349,17 +401,16 @@
|
||||||
//#define USE_SMALL_INFOFONT
|
//#define USE_SMALL_INFOFONT
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
|
|
||||||
// @section more
|
// @section more
|
||||||
|
|
||||||
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
||||||
//#define USE_WATCHDOG
|
#define USE_WATCHDOG
|
||||||
|
|
||||||
#if ENABLED(USE_WATCHDOG)
|
#if ENABLED(USE_WATCHDOG)
|
||||||
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
||||||
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
||||||
// 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.
|
// 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.
|
||||||
//#define WATCHDOG_RESET_MANUAL
|
//#define WATCHDOG_RESET_MANUAL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
@ -370,6 +421,7 @@
|
||||||
//#define BABYSTEPPING
|
//#define BABYSTEPPING
|
||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
||||||
|
//not implemented for deltabots!
|
||||||
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
||||||
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
||||||
#endif
|
#endif
|
||||||
|
@ -388,7 +440,6 @@
|
||||||
#if ENABLED(ADVANCE)
|
#if ENABLED(ADVANCE)
|
||||||
#define EXTRUDER_ADVANCE_K .0
|
#define EXTRUDER_ADVANCE_K .0
|
||||||
#define D_FILAMENT 1.75
|
#define D_FILAMENT 1.75
|
||||||
#define STEPS_MM_E 100.47095761381482
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
@ -397,7 +448,7 @@
|
||||||
#define MM_PER_ARC_SEGMENT 1
|
#define MM_PER_ARC_SEGMENT 1
|
||||||
#define N_ARC_CORRECTION 25
|
#define N_ARC_CORRECTION 25
|
||||||
|
|
||||||
const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
|
@ -446,11 +497,11 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt
|
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt
|
||||||
#define RETRACT_LENGTH 3 //default retract length (positive mm)
|
#define RETRACT_LENGTH 3 //default retract length (positive mm)
|
||||||
#define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change
|
#define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change
|
||||||
#define RETRACT_FEEDRATE 80*60 //default feedrate for retracting (mm/s)
|
#define RETRACT_FEEDRATE 80 //default feedrate for retracting (mm/s)
|
||||||
#define RETRACT_ZLIFT 0 //default retract Z-lift
|
#define RETRACT_ZLIFT 0 //default retract Z-lift
|
||||||
#define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering)
|
#define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering)
|
||||||
//#define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change)
|
//#define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change)
|
||||||
#define RETRACT_RECOVER_FEEDRATE 8*60 //default feedrate for recovering from retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Add support for experimental filament exchange support M600; requires display
|
// Add support for experimental filament exchange support M600; requires display
|
||||||
|
@ -462,12 +513,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
#define FILAMENTCHANGE_ZADD 10
|
#define FILAMENTCHANGE_ZADD 10
|
||||||
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||||
#define FILAMENTCHANGE_FINALRETRACT -100
|
#define FILAMENTCHANGE_FINALRETRACT -100
|
||||||
|
#define AUTO_FILAMENT_CHANGE //This extrude filament until you press the button on LCD
|
||||||
|
#define AUTO_FILAMENT_CHANGE_LENGTH 0.04 //Extrusion length on automatic extrusion loop
|
||||||
|
#define AUTO_FILAMENT_CHANGE_FEEDRATE 300 //Extrusion feedrate (mm/min) on automatic extrusion loop
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have TMC26X motor drivers.
|
* enable this section if you have TMC26X motor drivers.
|
||||||
* you need to import the TMC26XStepper library into the arduino IDE for this
|
* you need to import the TMC26XStepper library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section tmc
|
// @section tmc
|
||||||
|
@ -475,52 +529,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_TMCDRIVER
|
//#define HAVE_TMCDRIVER
|
||||||
#if ENABLED(HAVE_TMCDRIVER)
|
#if ENABLED(HAVE_TMCDRIVER)
|
||||||
|
|
||||||
//#define X_IS_TMC
|
//#define X_IS_TMC
|
||||||
#define X_MAX_CURRENT 1000 //in mA
|
#define X_MAX_CURRENT 1000 //in mA
|
||||||
#define X_SENSE_RESISTOR 91 //in mOhms
|
#define X_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define X2_IS_TMC
|
//#define X2_IS_TMC
|
||||||
#define X2_MAX_CURRENT 1000 //in mA
|
#define X2_MAX_CURRENT 1000 //in mA
|
||||||
#define X2_SENSE_RESISTOR 91 //in mOhms
|
#define X2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y_IS_TMC
|
//#define Y_IS_TMC
|
||||||
#define Y_MAX_CURRENT 1000 //in mA
|
#define Y_MAX_CURRENT 1000 //in mA
|
||||||
#define Y_SENSE_RESISTOR 91 //in mOhms
|
#define Y_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y2_IS_TMC
|
//#define Y2_IS_TMC
|
||||||
#define Y2_MAX_CURRENT 1000 //in mA
|
#define Y2_MAX_CURRENT 1000 //in mA
|
||||||
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z_IS_TMC
|
//#define Z_IS_TMC
|
||||||
#define Z_MAX_CURRENT 1000 //in mA
|
#define Z_MAX_CURRENT 1000 //in mA
|
||||||
#define Z_SENSE_RESISTOR 91 //in mOhms
|
#define Z_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z2_IS_TMC
|
//#define Z2_IS_TMC
|
||||||
#define Z2_MAX_CURRENT 1000 //in mA
|
#define Z2_MAX_CURRENT 1000 //in mA
|
||||||
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E0_IS_TMC
|
//#define E0_IS_TMC
|
||||||
#define E0_MAX_CURRENT 1000 //in mA
|
#define E0_MAX_CURRENT 1000 //in mA
|
||||||
#define E0_SENSE_RESISTOR 91 //in mOhms
|
#define E0_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E1_IS_TMC
|
//#define E1_IS_TMC
|
||||||
#define E1_MAX_CURRENT 1000 //in mA
|
#define E1_MAX_CURRENT 1000 //in mA
|
||||||
#define E1_SENSE_RESISTOR 91 //in mOhms
|
#define E1_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E2_IS_TMC
|
//#define E2_IS_TMC
|
||||||
#define E2_MAX_CURRENT 1000 //in mA
|
#define E2_MAX_CURRENT 1000 //in mA
|
||||||
#define E2_SENSE_RESISTOR 91 //in mOhms
|
#define E2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E3_IS_TMC
|
//#define E3_IS_TMC
|
||||||
#define E3_MAX_CURRENT 1000 //in mA
|
#define E3_MAX_CURRENT 1000 //in mA
|
||||||
#define E3_SENSE_RESISTOR 91 //in mOhms
|
#define E3_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
|
@ -529,7 +583,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have L6470 motor drivers.
|
* enable this section if you have L6470 motor drivers.
|
||||||
* you need to import the L6470 library into the arduino IDE for this
|
* you need to import the L6470 library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section l6470
|
// @section l6470
|
||||||
|
@ -537,63 +591,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_L6470DRIVER
|
//#define HAVE_L6470DRIVER
|
||||||
#if ENABLED(HAVE_L6470DRIVER)
|
#if ENABLED(HAVE_L6470DRIVER)
|
||||||
|
|
||||||
//#define X_IS_L6470
|
//#define X_IS_L6470
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define X2_IS_L6470
|
//#define X2_IS_L6470
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y_IS_L6470
|
//#define Y_IS_L6470
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y2_IS_L6470
|
//#define Y2_IS_L6470
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z_IS_L6470
|
//#define Z_IS_L6470
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z2_IS_L6470
|
//#define Z2_IS_L6470
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E0_IS_L6470
|
//#define E0_IS_L6470
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E1_IS_L6470
|
//#define E1_IS_L6470
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E2_IS_L6470
|
//#define E2_IS_L6470
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E3_IS_L6470
|
//#define E3_IS_L6470
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,40 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -7,8 +44,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -16,11 +55,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -70,7 +105,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// The following define selects which electronics board you have.
|
// The following define selects which electronics board you have.
|
||||||
// Please choose the name from boards.h that matches your setup
|
// Please choose the name from boards.h that matches your setup
|
||||||
#ifndef MOTHERBOARD
|
#ifndef MOTHERBOARD
|
||||||
#define MOTHERBOARD BOARD_RAMPS_13_EFB
|
#define MOTHERBOARD BOARD_RAMPS_14_EFB
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Optional custom name for your RepStrap or other custom machine
|
// Optional custom name for your RepStrap or other custom machine
|
||||||
|
@ -110,6 +145,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -129,6 +165,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -144,7 +181,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 1
|
#define TEMP_SENSOR_0 1
|
||||||
#define TEMP_SENSOR_1 0
|
#define TEMP_SENSOR_1 0
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
|
@ -178,14 +215,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define HEATER_3_MAXTEMP 275
|
#define HEATER_3_MAXTEMP 275
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
|
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
|
||||||
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
|
//#define BED_WATTS (12.0*12.0/1.1) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -197,6 +229,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
|
@ -247,19 +280,19 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
|
|
||||||
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||||
#define DEFAULT_bedKp 10.00
|
#define DEFAULT_bedKp 10.00
|
||||||
#define DEFAULT_bedKi .023
|
#define DEFAULT_bedKi .023
|
||||||
#define DEFAULT_bedKd 305.4
|
#define DEFAULT_bedKd 305.4
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from pidautotune
|
//from pidautotune
|
||||||
//#define DEFAULT_bedKp 97.1
|
//#define DEFAULT_bedKp 97.1
|
||||||
//#define DEFAULT_bedKi 1.41
|
//#define DEFAULT_bedKi 1.41
|
||||||
|
@ -284,16 +317,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -314,8 +346,22 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
#define USE_XMIN_PLUG
|
||||||
|
#define USE_YMIN_PLUG
|
||||||
|
#define USE_ZMIN_PLUG
|
||||||
|
//#define USE_XMAX_PLUG
|
||||||
|
//#define USE_YMAX_PLUG
|
||||||
|
//#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -338,13 +384,53 @@ const bool X_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
//#define DISABLE_MAX_ENDSTOPS
|
|
||||||
//#define DISABLE_MIN_ENDSTOPS
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -354,11 +440,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z false
|
#define DISABLE_Z false
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -381,6 +469,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define INVERT_E3_DIR false
|
#define INVERT_E3_DIR false
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
@ -416,24 +506,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
|
||||||
#define MESH_MIN_Y 10
|
#define MESH_MIN_Y 10
|
||||||
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
|
#define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -442,10 +534,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section bedlevel
|
// @section bedlevel
|
||||||
|
|
||||||
|
|
||||||
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
//#define DEBUG_LEVELING_FEATURE
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
|
@ -457,7 +548,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -471,7 +562,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define FRONT_PROBE_BED_POSITION 20
|
#define FRONT_PROBE_BED_POSITION 20
|
||||||
#define BACK_PROBE_BED_POSITION 170
|
#define BACK_PROBE_BED_POSITION 170
|
||||||
|
|
||||||
#define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
|
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
|
||||||
|
|
||||||
// Set the number of grid points per dimension.
|
// Set the number of grid points per dimension.
|
||||||
// You probably don't need more than 3 (squared=9).
|
// You probably don't need more than 3 (squared=9).
|
||||||
|
@ -479,25 +570,37 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X 15
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y 180
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X 15
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y 20
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X 170
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
|
@ -505,16 +608,29 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
||||||
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 15 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
//#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
|
@ -528,37 +644,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
|
||||||
|
@ -632,6 +717,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -652,13 +745,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
@ -666,11 +759,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
#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)
|
||||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
||||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
|
@ -687,13 +781,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
#define ELB_FULL_GRAPHIC_CONTROLLER
|
#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -708,7 +802,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
@ -731,6 +825,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -744,7 +840,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
// SSD1306 OLED generic display support
|
// SSD1306 OLED generic display support
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define U8GLIB_SSD1306
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
|
@ -756,7 +852,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
//#define FAST_PWM_FAN
|
//#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
@ -836,21 +932,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#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
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
|
|
||||||
//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.
|
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
|
@ -1,3 +1,40 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -7,8 +44,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -16,11 +55,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -110,6 +145,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -129,6 +165,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -144,7 +181,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 5
|
#define TEMP_SENSOR_0 5
|
||||||
#define TEMP_SENSOR_1 5
|
#define TEMP_SENSOR_1 5
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
|
@ -178,14 +215,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define HEATER_3_MAXTEMP 275
|
#define HEATER_3_MAXTEMP 275
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
|
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
|
||||||
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
|
//#define BED_WATTS (12.0*12.0/1.1) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -197,6 +229,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
|
@ -247,19 +280,19 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
|
|
||||||
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||||
#define DEFAULT_bedKp 10.00
|
#define DEFAULT_bedKp 10.00
|
||||||
#define DEFAULT_bedKi .023
|
#define DEFAULT_bedKi .023
|
||||||
#define DEFAULT_bedKd 305.4
|
#define DEFAULT_bedKd 305.4
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from pidautotune
|
//from pidautotune
|
||||||
//#define DEFAULT_bedKp 97.1
|
//#define DEFAULT_bedKp 97.1
|
||||||
//#define DEFAULT_bedKi 1.41
|
//#define DEFAULT_bedKi 1.41
|
||||||
|
@ -284,16 +317,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -349,8 +381,22 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
//#define USE_XMIN_PLUG
|
||||||
|
//#define USE_YMIN_PLUG
|
||||||
|
//#define USE_ZMIN_PLUG
|
||||||
|
#define USE_XMAX_PLUG
|
||||||
|
#define USE_YMAX_PLUG
|
||||||
|
#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -373,13 +419,53 @@ const bool X_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
//#define DISABLE_MAX_ENDSTOPS
|
|
||||||
#define DISABLE_MIN_ENDSTOPS // Deltas only use min endstops for probing.
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -389,11 +475,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z false
|
#define DISABLE_Z false
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -416,6 +504,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define INVERT_E3_DIR false
|
#define INVERT_E3_DIR false
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
@ -451,24 +541,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
|
||||||
#define MESH_MIN_Y 10
|
#define MESH_MIN_Y 10
|
||||||
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
|
#define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -479,7 +571,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
//#define DEBUG_LEVELING_FEATURE
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
//#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
//#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
|
@ -491,7 +583,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -501,41 +593,53 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#if ENABLED(AUTO_BED_LEVELING_GRID)
|
#if ENABLED(AUTO_BED_LEVELING_GRID)
|
||||||
|
|
||||||
// Set the rectangle in which to probe.
|
// Set the rectangle in which to probe.
|
||||||
#define DELTA_PROBABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
|
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
|
||||||
#define LEFT_PROBE_BED_POSITION -DELTA_PROBABLE_RADIUS
|
#define LEFT_PROBE_BED_POSITION -DELTA_PROBEABLE_RADIUS
|
||||||
#define RIGHT_PROBE_BED_POSITION DELTA_PROBABLE_RADIUS
|
#define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
|
||||||
#define FRONT_PROBE_BED_POSITION -DELTA_PROBABLE_RADIUS
|
#define FRONT_PROBE_BED_POSITION -DELTA_PROBEABLE_RADIUS
|
||||||
#define BACK_PROBE_BED_POSITION DELTA_PROBABLE_RADIUS
|
#define BACK_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
|
||||||
|
|
||||||
#define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
|
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
|
||||||
|
|
||||||
// Non-linear bed leveling will be used.
|
// Non-linear bed leveling will be used.
|
||||||
// Compensate by interpolating between the nearest four Z probe values for each point.
|
// Compensate by interpolating between the nearest four Z probe values for each point.
|
||||||
// Useful for deltas where the print surface may appear like a bowl or dome shape.
|
// Useful for deltas where the print surface may appear like a bowl or dome shape.
|
||||||
// Works best with ACCURATE_BED_LEVELING_POINTS 5 or higher.
|
// Works best with AUTO_BED_LEVELING_GRID_POINTS 5 or higher.
|
||||||
#define AUTO_BED_LEVELING_GRID_POINTS 9
|
#define AUTO_BED_LEVELING_GRID_POINTS 9
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X 15
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y 180
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X 15
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y 20
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X 170
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 0 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -10 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -3.5 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER 0 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER -10 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -3.5 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 4000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 4000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
|
@ -543,10 +647,22 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points.
|
||||||
#define Z_RAISE_AFTER_PROBING 50 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 50 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
//#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
// Allen key retractable Z probe as seen on many Kossel delta printers - http://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe
|
// Allen key retractable Z probe as seen on many Kossel delta printers - http://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe
|
||||||
|
@ -630,10 +746,11 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE HOMING_FEEDRATE_XYZ
|
#define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE HOMING_FEEDRATE_XYZ
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
|
@ -647,37 +764,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
|
||||||
|
@ -710,7 +796,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// delta speeds must be the same on xyz
|
// delta speeds must be the same on xyz
|
||||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {72.9, 72.9, 72.9, 291} // default steps per unit for BI v2.5 (cable drive)
|
#define DEFAULT_AXIS_STEPS_PER_UNIT {72.9, 72.9, 72.9, 291} // default steps per unit for BI v2.5 (cable drive)
|
||||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 500, 150} // (mm/sec)
|
#define DEFAULT_MAX_FEEDRATE {500, 500, 500, 150} // (mm/sec)
|
||||||
#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.
|
#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.
|
||||||
|
|
||||||
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
|
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
|
||||||
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
|
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
|
||||||
|
@ -753,6 +839,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -773,13 +867,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
@ -787,12 +881,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
//#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)
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
|
||||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
||||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
|
@ -809,13 +903,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -830,7 +924,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
@ -843,6 +937,10 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
||||||
//#define RA_CONTROL_PANEL
|
//#define RA_CONTROL_PANEL
|
||||||
|
|
||||||
|
// The MakerLab Mini Panel with graphic controller and SD support
|
||||||
|
// http://reprap.org/wiki/Mini_panel
|
||||||
|
//#define MINIPANEL
|
||||||
|
|
||||||
// Delta calibration menu
|
// Delta calibration menu
|
||||||
// uncomment to add three points calibration menu option.
|
// uncomment to add three points calibration menu option.
|
||||||
// See http://minow.blogspot.com/index.html#4918805519571907051
|
// See http://minow.blogspot.com/index.html#4918805519571907051
|
||||||
|
@ -856,6 +954,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -869,7 +969,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
// SSD1306 OLED generic display support
|
// SSD1306 OLED generic display support
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define U8GLIB_SSD1306
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
|
@ -881,7 +981,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
//#define FAST_PWM_FAN
|
//#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
@ -961,21 +1061,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
#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
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
//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.
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
|
@ -1,3 +1,35 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration_adv.h
|
||||||
|
*
|
||||||
|
* Advanced settings.
|
||||||
|
* Only change these if you know exactly what you're doing.
|
||||||
|
* Some of these settings can damage your printer if improperly set!
|
||||||
|
*
|
||||||
|
* Basic settings can be found in Configuration.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
|
|
||||||
|
@ -9,13 +41,26 @@
|
||||||
//=============================Thermal Settings ============================
|
//=============================Thermal Settings ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
#if DISABLED(PIDTEMPBED)
|
||||||
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||||
|
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||||
|
#define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection parameters
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
|
*
|
||||||
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
|
*
|
||||||
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
|
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
||||||
|
* the firmware will halt the machine as a safety precaution.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
|
||||||
*/
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
||||||
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
||||||
|
@ -26,26 +71,24 @@
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* but only if the current temperature is far enough below the target for a reliable test.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
|
||||||
|
* WATCH_TEMP_INCREASE should not be below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 16 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 4 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Thermal Protection parameters for the bed
|
||||||
|
* are like the above for the hotends.
|
||||||
|
* WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
|
||||||
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_BED)
|
#if ENABLED(THERMAL_PROTECTION_BED)
|
||||||
#define THERMAL_PROTECTION_BED_PERIOD 120 // Seconds
|
#define THERMAL_PROTECTION_BED_PERIOD 120 // Seconds
|
||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 4 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
|
||||||
* Automatic Temperature:
|
|
||||||
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
|
||||||
* The maximum buffered steps/sec of the extruder motor is called "se".
|
|
||||||
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
|
||||||
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
|
||||||
* mintemp and maxtemp. Turn this off by excuting M109 without F*
|
|
||||||
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
|
||||||
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
|
||||||
*/
|
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||||
|
@ -56,14 +99,16 @@
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
|
* Automatic Temperature:
|
||||||
//The maximum buffered steps/sec of the extruder motor are called "se".
|
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
||||||
//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
|
* The maximum buffered steps/sec of the extruder motor is called "se".
|
||||||
// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
|
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
||||||
// you exit the value by any M109 without F*
|
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
||||||
// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
|
* mintemp and maxtemp. Turn this off by executing M109 without F*
|
||||||
// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
||||||
|
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
||||||
|
*/
|
||||||
#define AUTOTEMP
|
#define AUTOTEMP
|
||||||
#if ENABLED(AUTOTEMP)
|
#if ENABLED(AUTOTEMP)
|
||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
|
@ -156,9 +201,7 @@
|
||||||
//#define Z_DUAL_ENDSTOPS
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_MAX_PIN 36 //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36)
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
const bool Z2_MAX_ENDSTOP_INVERTING = false;
|
|
||||||
#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.
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
#endif // Z_DUAL_STEPPER_DRIVERS
|
||||||
|
@ -240,7 +283,13 @@
|
||||||
#define INVERT_E_STEP_PIN false
|
#define INVERT_E_STEP_PIN false
|
||||||
|
|
||||||
// Default stepper release if idle. Set to 0 to deactivate.
|
// Default stepper release if idle. Set to 0 to deactivate.
|
||||||
|
// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
|
||||||
|
// Time can be set by M18 and M84.
|
||||||
#define DEFAULT_STEPPER_DEACTIVE_TIME 0
|
#define DEFAULT_STEPPER_DEACTIVE_TIME 0
|
||||||
|
#define DISABLE_INACTIVE_X true
|
||||||
|
#define DISABLE_INACTIVE_Y true
|
||||||
|
#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished.
|
||||||
|
#define DISABLE_INACTIVE_E true
|
||||||
|
|
||||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
||||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
||||||
|
@ -278,6 +327,9 @@
|
||||||
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
||||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||||
|
|
||||||
|
// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
|
||||||
|
//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
|
||||||
|
|
||||||
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
||||||
|
@ -354,13 +406,13 @@
|
||||||
// @section more
|
// @section more
|
||||||
|
|
||||||
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
||||||
//#define USE_WATCHDOG
|
#define USE_WATCHDOG
|
||||||
|
|
||||||
#if ENABLED(USE_WATCHDOG)
|
#if ENABLED(USE_WATCHDOG)
|
||||||
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
||||||
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
||||||
// 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.
|
// 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.
|
||||||
//#define WATCHDOG_RESET_MANUAL
|
//#define WATCHDOG_RESET_MANUAL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
@ -371,6 +423,7 @@
|
||||||
//#define BABYSTEPPING
|
//#define BABYSTEPPING
|
||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
||||||
|
//not implemented for deltabots!
|
||||||
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
||||||
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
||||||
#endif
|
#endif
|
||||||
|
@ -389,7 +442,6 @@
|
||||||
#if ENABLED(ADVANCE)
|
#if ENABLED(ADVANCE)
|
||||||
#define EXTRUDER_ADVANCE_K .0
|
#define EXTRUDER_ADVANCE_K .0
|
||||||
#define D_FILAMENT 2.85
|
#define D_FILAMENT 2.85
|
||||||
#define STEPS_MM_E 836
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
@ -398,7 +450,7 @@
|
||||||
#define MM_PER_ARC_SEGMENT 1
|
#define MM_PER_ARC_SEGMENT 1
|
||||||
#define N_ARC_CORRECTION 25
|
#define N_ARC_CORRECTION 25
|
||||||
|
|
||||||
const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
|
@ -447,11 +499,11 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt
|
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt
|
||||||
#define RETRACT_LENGTH 5 //default retract length (positive mm)
|
#define RETRACT_LENGTH 5 //default retract length (positive mm)
|
||||||
#define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change
|
#define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change
|
||||||
#define RETRACT_FEEDRATE 100 //default feedrate for retracting (mm/s)
|
#define RETRACT_FEEDRATE 100 //default feedrate for retracting (mm/s)
|
||||||
#define RETRACT_ZLIFT 0 //default retract Z-lift
|
#define RETRACT_ZLIFT 0 //default retract Z-lift
|
||||||
#define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering)
|
#define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering)
|
||||||
#define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change)
|
#define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change)
|
||||||
#define RETRACT_RECOVER_FEEDRATE 100 //default feedrate for recovering from retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE 100 //default feedrate for recovering from retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Add support for experimental filament exchange support M600; requires display
|
// Add support for experimental filament exchange support M600; requires display
|
||||||
|
@ -463,12 +515,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
#define FILAMENTCHANGE_ZADD 10
|
#define FILAMENTCHANGE_ZADD 10
|
||||||
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||||
#define FILAMENTCHANGE_FINALRETRACT -100
|
#define FILAMENTCHANGE_FINALRETRACT -100
|
||||||
|
#define AUTO_FILAMENT_CHANGE //This extrude filament until you press the button on LCD
|
||||||
|
#define AUTO_FILAMENT_CHANGE_LENGTH 0.04 //Extrusion length on automatic extrusion loop
|
||||||
|
#define AUTO_FILAMENT_CHANGE_FEEDRATE 300 //Extrusion feedrate (mm/min) on automatic extrusion loop
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have TMC26X motor drivers.
|
* enable this section if you have TMC26X motor drivers.
|
||||||
* you need to import the TMC26XStepper library into the arduino IDE for this
|
* you need to import the TMC26XStepper library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section tmc
|
// @section tmc
|
||||||
|
@ -476,52 +531,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_TMCDRIVER
|
//#define HAVE_TMCDRIVER
|
||||||
#if ENABLED(HAVE_TMCDRIVER)
|
#if ENABLED(HAVE_TMCDRIVER)
|
||||||
|
|
||||||
//#define X_IS_TMC
|
//#define X_IS_TMC
|
||||||
#define X_MAX_CURRENT 1000 //in mA
|
#define X_MAX_CURRENT 1000 //in mA
|
||||||
#define X_SENSE_RESISTOR 91 //in mOhms
|
#define X_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define X2_IS_TMC
|
//#define X2_IS_TMC
|
||||||
#define X2_MAX_CURRENT 1000 //in mA
|
#define X2_MAX_CURRENT 1000 //in mA
|
||||||
#define X2_SENSE_RESISTOR 91 //in mOhms
|
#define X2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y_IS_TMC
|
//#define Y_IS_TMC
|
||||||
#define Y_MAX_CURRENT 1000 //in mA
|
#define Y_MAX_CURRENT 1000 //in mA
|
||||||
#define Y_SENSE_RESISTOR 91 //in mOhms
|
#define Y_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y2_IS_TMC
|
//#define Y2_IS_TMC
|
||||||
#define Y2_MAX_CURRENT 1000 //in mA
|
#define Y2_MAX_CURRENT 1000 //in mA
|
||||||
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z_IS_TMC
|
//#define Z_IS_TMC
|
||||||
#define Z_MAX_CURRENT 1000 //in mA
|
#define Z_MAX_CURRENT 1000 //in mA
|
||||||
#define Z_SENSE_RESISTOR 91 //in mOhms
|
#define Z_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z2_IS_TMC
|
//#define Z2_IS_TMC
|
||||||
#define Z2_MAX_CURRENT 1000 //in mA
|
#define Z2_MAX_CURRENT 1000 //in mA
|
||||||
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E0_IS_TMC
|
//#define E0_IS_TMC
|
||||||
#define E0_MAX_CURRENT 1000 //in mA
|
#define E0_MAX_CURRENT 1000 //in mA
|
||||||
#define E0_SENSE_RESISTOR 91 //in mOhms
|
#define E0_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E1_IS_TMC
|
//#define E1_IS_TMC
|
||||||
#define E1_MAX_CURRENT 1000 //in mA
|
#define E1_MAX_CURRENT 1000 //in mA
|
||||||
#define E1_SENSE_RESISTOR 91 //in mOhms
|
#define E1_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E2_IS_TMC
|
//#define E2_IS_TMC
|
||||||
#define E2_MAX_CURRENT 1000 //in mA
|
#define E2_MAX_CURRENT 1000 //in mA
|
||||||
#define E2_SENSE_RESISTOR 91 //in mOhms
|
#define E2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E3_IS_TMC
|
//#define E3_IS_TMC
|
||||||
#define E3_MAX_CURRENT 1000 //in mA
|
#define E3_MAX_CURRENT 1000 //in mA
|
||||||
#define E3_SENSE_RESISTOR 91 //in mOhms
|
#define E3_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
|
@ -530,7 +585,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have L6470 motor drivers.
|
* enable this section if you have L6470 motor drivers.
|
||||||
* you need to import the L6470 library into the arduino IDE for this
|
* you need to import the L6470 library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section l6470
|
// @section l6470
|
||||||
|
@ -538,63 +593,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_L6470DRIVER
|
//#define HAVE_L6470DRIVER
|
||||||
#if ENABLED(HAVE_L6470DRIVER)
|
#if ENABLED(HAVE_L6470DRIVER)
|
||||||
|
|
||||||
//#define X_IS_L6470
|
//#define X_IS_L6470
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define X2_IS_L6470
|
//#define X2_IS_L6470
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y_IS_L6470
|
//#define Y_IS_L6470
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y2_IS_L6470
|
//#define Y2_IS_L6470
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z_IS_L6470
|
//#define Z_IS_L6470
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z2_IS_L6470
|
//#define Z2_IS_L6470
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E0_IS_L6470
|
//#define E0_IS_L6470
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E1_IS_L6470
|
//#define E1_IS_L6470
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E2_IS_L6470
|
//#define E2_IS_L6470
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E3_IS_L6470
|
//#define E3_IS_L6470
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,40 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -7,8 +44,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -16,11 +55,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -70,7 +105,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// The following define selects which electronics board you have.
|
// The following define selects which electronics board you have.
|
||||||
// Please choose the name from boards.h that matches your setup
|
// Please choose the name from boards.h that matches your setup
|
||||||
#ifndef MOTHERBOARD
|
#ifndef MOTHERBOARD
|
||||||
#define MOTHERBOARD BOARD_RAMPS_13_EFB
|
#define MOTHERBOARD BOARD_RAMPS_14_EFB
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Optional custom name for your RepStrap or other custom machine
|
// Optional custom name for your RepStrap or other custom machine
|
||||||
|
@ -110,6 +145,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -129,6 +165,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -144,7 +181,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 -1
|
#define TEMP_SENSOR_0 -1
|
||||||
#define TEMP_SENSOR_1 -1
|
#define TEMP_SENSOR_1 -1
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
|
@ -178,14 +215,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define HEATER_3_MAXTEMP 275
|
#define HEATER_3_MAXTEMP 275
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
|
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
|
||||||
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
|
//#define BED_WATTS (12.0*12.0/1.1) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -197,6 +229,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
|
@ -247,19 +280,19 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
|
|
||||||
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||||
#define DEFAULT_bedKp 10.00
|
#define DEFAULT_bedKp 10.00
|
||||||
#define DEFAULT_bedKi .023
|
#define DEFAULT_bedKi .023
|
||||||
#define DEFAULT_bedKd 305.4
|
#define DEFAULT_bedKd 305.4
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from pidautotune
|
//from pidautotune
|
||||||
//#define DEFAULT_bedKp 97.1
|
//#define DEFAULT_bedKp 97.1
|
||||||
//#define DEFAULT_bedKi 1.41
|
//#define DEFAULT_bedKi 1.41
|
||||||
|
@ -284,16 +317,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -349,8 +381,22 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
//#define USE_XMIN_PLUG
|
||||||
|
//#define USE_YMIN_PLUG
|
||||||
|
#define USE_ZMIN_PLUG // a Z probe
|
||||||
|
#define USE_XMAX_PLUG
|
||||||
|
#define USE_YMAX_PLUG
|
||||||
|
#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -373,13 +419,53 @@ const bool X_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
|
||||||
//#define DISABLE_MAX_ENDSTOPS
|
|
||||||
#define DISABLE_MIN_ENDSTOPS // Deltas only use min endstops for probing.
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
//#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -389,11 +475,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z false
|
#define DISABLE_Z false
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -416,6 +504,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define INVERT_E3_DIR false
|
#define INVERT_E3_DIR false
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
//#define MIN_Z_HEIGHT_FOR_HOMING 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
@ -451,24 +541,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
|
||||||
#define MESH_MIN_Y 10
|
#define MESH_MIN_Y 10
|
||||||
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
|
#define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -477,14 +569,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
// @section bedlevel
|
// @section bedlevel
|
||||||
|
|
||||||
|
|
||||||
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
//#define DEBUG_LEVELING_FEATURE
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
//#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
//#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
// There are 2 different ways to specify probing locations.
|
// There are 2 different ways to specify probing locations:
|
||||||
//
|
//
|
||||||
// - "grid" mode
|
// - "grid" mode
|
||||||
// Probe several points in a rectangular grid.
|
// Probe several points in a rectangular grid.
|
||||||
|
@ -492,7 +583,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -502,41 +593,53 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#if ENABLED(AUTO_BED_LEVELING_GRID)
|
#if ENABLED(AUTO_BED_LEVELING_GRID)
|
||||||
|
|
||||||
// set the rectangle in which to probe
|
// set the rectangle in which to probe
|
||||||
#define DELTA_PROBABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
|
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
|
||||||
#define LEFT_PROBE_BED_POSITION -DELTA_PROBABLE_RADIUS
|
#define LEFT_PROBE_BED_POSITION -DELTA_PROBEABLE_RADIUS
|
||||||
#define RIGHT_PROBE_BED_POSITION DELTA_PROBABLE_RADIUS
|
#define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
|
||||||
#define FRONT_PROBE_BED_POSITION -DELTA_PROBABLE_RADIUS
|
#define FRONT_PROBE_BED_POSITION -DELTA_PROBEABLE_RADIUS
|
||||||
#define BACK_PROBE_BED_POSITION DELTA_PROBABLE_RADIUS
|
#define BACK_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
|
||||||
|
|
||||||
#define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
|
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
|
||||||
|
|
||||||
// Non-linear bed leveling will be used.
|
// Non-linear bed leveling will be used.
|
||||||
// Compensate by interpolating between the nearest four Z probe values for each point.
|
// Compensate by interpolating between the nearest four Z probe values for each point.
|
||||||
// Useful for deltas where the print surface may appear like a bowl or dome shape.
|
// Useful for deltas where the print surface may appear like a bowl or dome shape.
|
||||||
// Works best with ACCURATE_BED_LEVELING_POINTS 5 or higher.
|
// Works best with AUTO_BED_LEVELING_GRID_POINTS 5 or higher.
|
||||||
#define AUTO_BED_LEVELING_GRID_POINTS 9
|
#define AUTO_BED_LEVELING_GRID_POINTS 9
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X 15
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y 180
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X 15
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y 20
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X 170
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 0 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -10 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -3.5 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER 0 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER -10 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -3.5 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 4000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 4000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
|
@ -544,13 +647,25 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points
|
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points
|
||||||
#define Z_RAISE_AFTER_PROBING 50 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 50 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
//#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
// Allen key retractable z-probe as seen on many Kossel delta printers - http://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe
|
// Allen key retractable Z probe as seen on many Kossel delta printers - http://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe
|
||||||
// Deploys by touching z-axis belt. Retracts by pushing the probe down. Uses Z_MIN_PIN.
|
// Deploys by touching z-axis belt. Retracts by pushing the probe down. Uses Z_MIN_PIN.
|
||||||
//#define Z_PROBE_ALLEN_KEY
|
//#define Z_PROBE_ALLEN_KEY
|
||||||
|
|
||||||
|
@ -631,10 +746,11 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
//#define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE HOMING_FEEDRATE_XYZ
|
//#define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE HOMING_FEEDRATE_XYZ
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
|
@ -648,37 +764,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
|
||||||
|
@ -711,7 +796,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// delta speeds must be the same on xyz
|
// delta speeds must be the same on xyz
|
||||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {80, 80, 80, 760*1.1} // default steps per unit for Kossel (GT2, 20 tooth)
|
#define DEFAULT_AXIS_STEPS_PER_UNIT {80, 80, 80, 760*1.1} // default steps per unit for Kossel (GT2, 20 tooth)
|
||||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 500, 25} // (mm/sec)
|
#define DEFAULT_MAX_FEEDRATE {500, 500, 500, 25} // (mm/sec)
|
||||||
#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.
|
#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.
|
||||||
|
|
||||||
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
|
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
|
||||||
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
|
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
|
||||||
|
@ -754,6 +839,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -774,13 +867,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
@ -788,12 +881,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
//#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)
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
|
||||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
||||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
|
@ -810,13 +903,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -831,7 +924,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
@ -844,6 +937,10 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
||||||
//#define RA_CONTROL_PANEL
|
//#define RA_CONTROL_PANEL
|
||||||
|
|
||||||
|
// The MakerLab Mini Panel with graphic controller and SD support
|
||||||
|
// http://reprap.org/wiki/Mini_panel
|
||||||
|
//#define MINIPANEL
|
||||||
|
|
||||||
// Delta calibration menu
|
// Delta calibration menu
|
||||||
// uncomment to add three points calibration menu option.
|
// uncomment to add three points calibration menu option.
|
||||||
// See http://minow.blogspot.com/index.html#4918805519571907051
|
// See http://minow.blogspot.com/index.html#4918805519571907051
|
||||||
|
@ -851,16 +948,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
// in ultralcd.cpp@lcd_delta_calibrate_menu()
|
// in ultralcd.cpp@lcd_delta_calibrate_menu()
|
||||||
//#define DELTA_CALIBRATION_MENU
|
//#define DELTA_CALIBRATION_MENU
|
||||||
|
|
||||||
// The MakerLab Mini Panel with graphic controller and SD support
|
|
||||||
// http://reprap.org/wiki/Mini_panel
|
|
||||||
//#define MINIPANEL
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* I2C Panels
|
* I2C Panels
|
||||||
*/
|
*/
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -874,7 +969,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
// SSD1306 OLED generic display support
|
// SSD1306 OLED generic display support
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define U8GLIB_SSD1306
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
|
@ -886,7 +981,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
//#define FAST_PWM_FAN
|
//#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
@ -966,21 +1061,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the lo
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#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
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
|
|
||||||
//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.
|
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
|
@ -1,3 +1,35 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration_adv.h
|
||||||
|
*
|
||||||
|
* Advanced settings.
|
||||||
|
* Only change these if you know exactly what you're doing.
|
||||||
|
* Some of these settings can damage your printer if improperly set!
|
||||||
|
*
|
||||||
|
* Basic settings can be found in Configuration.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
|
|
||||||
|
@ -9,13 +41,26 @@
|
||||||
//=============================Thermal Settings ============================
|
//=============================Thermal Settings ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#if ENABLED(BED_LIMIT_SWITCHING)
|
#if DISABLED(PIDTEMPBED)
|
||||||
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
|
||||||
|
#if ENABLED(BED_LIMIT_SWITCHING)
|
||||||
|
#define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection parameters
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
|
*
|
||||||
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
|
*
|
||||||
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
|
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
||||||
|
* the firmware will halt the machine as a safety precaution.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
|
||||||
*/
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
|
||||||
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
|
||||||
|
@ -26,26 +71,24 @@
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* but only if the current temperature is far enough below the target for a reliable test.
|
||||||
|
*
|
||||||
|
* If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
|
||||||
|
* WATCH_TEMP_INCREASE should not be below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 16 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 4 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Thermal Protection parameters for the bed
|
||||||
|
* are like the above for the hotends.
|
||||||
|
* WATCH_TEMP_BED_PERIOD and WATCH_TEMP_BED_INCREASE are not imlemented now.
|
||||||
|
*/
|
||||||
#if ENABLED(THERMAL_PROTECTION_BED)
|
#if ENABLED(THERMAL_PROTECTION_BED)
|
||||||
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
|
||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
|
||||||
* Automatic Temperature:
|
|
||||||
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
|
||||||
* The maximum buffered steps/sec of the extruder motor is called "se".
|
|
||||||
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
|
||||||
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
|
||||||
* mintemp and maxtemp. Turn this off by excuting M109 without F*
|
|
||||||
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
|
||||||
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
|
||||||
*/
|
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||||
|
@ -56,14 +99,16 @@
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
|
* Automatic Temperature:
|
||||||
//The maximum buffered steps/sec of the extruder motor are called "se".
|
* The hotend target temperature is calculated by all the buffered lines of gcode.
|
||||||
//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
|
* The maximum buffered steps/sec of the extruder motor is called "se".
|
||||||
// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
|
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor>
|
||||||
// you exit the value by any M109 without F*
|
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by
|
||||||
// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
|
* mintemp and maxtemp. Turn this off by executing M109 without F*
|
||||||
// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
* Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp.
|
||||||
|
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
|
||||||
|
*/
|
||||||
#define AUTOTEMP
|
#define AUTOTEMP
|
||||||
#if ENABLED(AUTOTEMP)
|
#if ENABLED(AUTOTEMP)
|
||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
|
@ -156,9 +201,7 @@
|
||||||
//#define Z_DUAL_ENDSTOPS
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_MAX_PIN 36 //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36)
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
const bool Z2_MAX_ENDSTOP_INVERTING = false;
|
|
||||||
#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.
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
#endif // Z_DUAL_STEPPER_DRIVERS
|
||||||
|
@ -240,7 +283,13 @@
|
||||||
#define INVERT_E_STEP_PIN false
|
#define INVERT_E_STEP_PIN false
|
||||||
|
|
||||||
// Default stepper release if idle. Set to 0 to deactivate.
|
// Default stepper release if idle. Set to 0 to deactivate.
|
||||||
|
// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
|
||||||
|
// Time can be set by M18 and M84.
|
||||||
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
|
||||||
|
#define DISABLE_INACTIVE_X true
|
||||||
|
#define DISABLE_INACTIVE_Y true
|
||||||
|
#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished.
|
||||||
|
#define DISABLE_INACTIVE_E true
|
||||||
|
|
||||||
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
|
||||||
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
#define DEFAULT_MINTRAVELFEEDRATE 0.0
|
||||||
|
@ -278,6 +327,9 @@
|
||||||
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
|
||||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
||||||
|
|
||||||
|
// Motor Current controlled via PWM (Overridable on supported boards with PWM-driven motor driver current)
|
||||||
|
//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps
|
||||||
|
|
||||||
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
|
||||||
|
@ -351,17 +403,16 @@
|
||||||
//#define USE_SMALL_INFOFONT
|
//#define USE_SMALL_INFOFONT
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
|
|
||||||
// @section more
|
// @section more
|
||||||
|
|
||||||
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
|
||||||
//#define USE_WATCHDOG
|
#define USE_WATCHDOG
|
||||||
|
|
||||||
#if ENABLED(USE_WATCHDOG)
|
#if ENABLED(USE_WATCHDOG)
|
||||||
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
|
||||||
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
|
||||||
// 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.
|
// 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.
|
||||||
//#define WATCHDOG_RESET_MANUAL
|
//#define WATCHDOG_RESET_MANUAL
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
@ -372,6 +423,7 @@
|
||||||
//#define BABYSTEPPING
|
//#define BABYSTEPPING
|
||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
|
||||||
|
//not implemented for deltabots!
|
||||||
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
|
||||||
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
|
||||||
#endif
|
#endif
|
||||||
|
@ -390,7 +442,6 @@
|
||||||
#if ENABLED(ADVANCE)
|
#if ENABLED(ADVANCE)
|
||||||
#define EXTRUDER_ADVANCE_K .0
|
#define EXTRUDER_ADVANCE_K .0
|
||||||
#define D_FILAMENT 2.85
|
#define D_FILAMENT 2.85
|
||||||
#define STEPS_MM_E 836
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
@ -399,7 +450,7 @@
|
||||||
#define MM_PER_ARC_SEGMENT 1
|
#define MM_PER_ARC_SEGMENT 1
|
||||||
#define N_ARC_CORRECTION 25
|
#define N_ARC_CORRECTION 25
|
||||||
|
|
||||||
const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
|
@ -464,12 +515,15 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
#define FILAMENTCHANGE_ZADD 10
|
#define FILAMENTCHANGE_ZADD 10
|
||||||
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
||||||
#define FILAMENTCHANGE_FINALRETRACT -100
|
#define FILAMENTCHANGE_FINALRETRACT -100
|
||||||
|
#define AUTO_FILAMENT_CHANGE //This extrude filament until you press the button on LCD
|
||||||
|
#define AUTO_FILAMENT_CHANGE_LENGTH 0.04 //Extrusion length on automatic extrusion loop
|
||||||
|
#define AUTO_FILAMENT_CHANGE_FEEDRATE 300 //Extrusion feedrate (mm/min) on automatic extrusion loop
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have TMC26X motor drivers.
|
* enable this section if you have TMC26X motor drivers.
|
||||||
* you need to import the TMC26XStepper library into the arduino IDE for this
|
* you need to import the TMC26XStepper library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section tmc
|
// @section tmc
|
||||||
|
@ -477,52 +531,52 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_TMCDRIVER
|
//#define HAVE_TMCDRIVER
|
||||||
#if ENABLED(HAVE_TMCDRIVER)
|
#if ENABLED(HAVE_TMCDRIVER)
|
||||||
|
|
||||||
//#define X_IS_TMC
|
//#define X_IS_TMC
|
||||||
#define X_MAX_CURRENT 1000 //in mA
|
#define X_MAX_CURRENT 1000 //in mA
|
||||||
#define X_SENSE_RESISTOR 91 //in mOhms
|
#define X_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define X2_IS_TMC
|
//#define X2_IS_TMC
|
||||||
#define X2_MAX_CURRENT 1000 //in mA
|
#define X2_MAX_CURRENT 1000 //in mA
|
||||||
#define X2_SENSE_RESISTOR 91 //in mOhms
|
#define X2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y_IS_TMC
|
//#define Y_IS_TMC
|
||||||
#define Y_MAX_CURRENT 1000 //in mA
|
#define Y_MAX_CURRENT 1000 //in mA
|
||||||
#define Y_SENSE_RESISTOR 91 //in mOhms
|
#define Y_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Y2_IS_TMC
|
//#define Y2_IS_TMC
|
||||||
#define Y2_MAX_CURRENT 1000 //in mA
|
#define Y2_MAX_CURRENT 1000 //in mA
|
||||||
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
#define Y2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z_IS_TMC
|
//#define Z_IS_TMC
|
||||||
#define Z_MAX_CURRENT 1000 //in mA
|
#define Z_MAX_CURRENT 1000 //in mA
|
||||||
#define Z_SENSE_RESISTOR 91 //in mOhms
|
#define Z_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define Z2_IS_TMC
|
//#define Z2_IS_TMC
|
||||||
#define Z2_MAX_CURRENT 1000 //in mA
|
#define Z2_MAX_CURRENT 1000 //in mA
|
||||||
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
#define Z2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E0_IS_TMC
|
//#define E0_IS_TMC
|
||||||
#define E0_MAX_CURRENT 1000 //in mA
|
#define E0_MAX_CURRENT 1000 //in mA
|
||||||
#define E0_SENSE_RESISTOR 91 //in mOhms
|
#define E0_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E1_IS_TMC
|
//#define E1_IS_TMC
|
||||||
#define E1_MAX_CURRENT 1000 //in mA
|
#define E1_MAX_CURRENT 1000 //in mA
|
||||||
#define E1_SENSE_RESISTOR 91 //in mOhms
|
#define E1_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E2_IS_TMC
|
//#define E2_IS_TMC
|
||||||
#define E2_MAX_CURRENT 1000 //in mA
|
#define E2_MAX_CURRENT 1000 //in mA
|
||||||
#define E2_SENSE_RESISTOR 91 //in mOhms
|
#define E2_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
|
|
||||||
//#define E3_IS_TMC
|
//#define E3_IS_TMC
|
||||||
#define E3_MAX_CURRENT 1000 //in mA
|
#define E3_MAX_CURRENT 1000 //in mA
|
||||||
#define E3_SENSE_RESISTOR 91 //in mOhms
|
#define E3_SENSE_RESISTOR 91 //in mOhms
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
|
@ -531,7 +585,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
|
|
||||||
/******************************************************************************\
|
/******************************************************************************\
|
||||||
* enable this section if you have L6470 motor drivers.
|
* enable this section if you have L6470 motor drivers.
|
||||||
* you need to import the L6470 library into the arduino IDE for this
|
* you need to import the L6470 library into the Arduino IDE for this
|
||||||
******************************************************************************/
|
******************************************************************************/
|
||||||
|
|
||||||
// @section l6470
|
// @section l6470
|
||||||
|
@ -539,63 +593,63 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//#define HAVE_L6470DRIVER
|
//#define HAVE_L6470DRIVER
|
||||||
#if ENABLED(HAVE_L6470DRIVER)
|
#if ENABLED(HAVE_L6470DRIVER)
|
||||||
|
|
||||||
//#define X_IS_L6470
|
//#define X_IS_L6470
|
||||||
#define X_MICROSTEPS 16 //number of microsteps
|
#define X_MICROSTEPS 16 //number of microsteps
|
||||||
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define X2_IS_L6470
|
//#define X2_IS_L6470
|
||||||
#define X2_MICROSTEPS 16 //number of microsteps
|
#define X2_MICROSTEPS 16 //number of microsteps
|
||||||
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y_IS_L6470
|
//#define Y_IS_L6470
|
||||||
#define Y_MICROSTEPS 16 //number of microsteps
|
#define Y_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Y2_IS_L6470
|
//#define Y2_IS_L6470
|
||||||
#define Y2_MICROSTEPS 16 //number of microsteps
|
#define Y2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z_IS_L6470
|
//#define Z_IS_L6470
|
||||||
#define Z_MICROSTEPS 16 //number of microsteps
|
#define Z_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define Z2_IS_L6470
|
//#define Z2_IS_L6470
|
||||||
#define Z2_MICROSTEPS 16 //number of microsteps
|
#define Z2_MICROSTEPS 16 //number of microsteps
|
||||||
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E0_IS_L6470
|
//#define E0_IS_L6470
|
||||||
#define E0_MICROSTEPS 16 //number of microsteps
|
#define E0_MICROSTEPS 16 //number of microsteps
|
||||||
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E1_IS_L6470
|
//#define E1_IS_L6470
|
||||||
#define E1_MICROSTEPS 16 //number of microsteps
|
#define E1_MICROSTEPS 16 //number of microsteps
|
||||||
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E2_IS_L6470
|
//#define E2_IS_L6470
|
||||||
#define E2_MICROSTEPS 16 //number of microsteps
|
#define E2_MICROSTEPS 16 //number of microsteps
|
||||||
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
//#define E3_IS_L6470
|
//#define E3_IS_L6470
|
||||||
#define E3_MICROSTEPS 16 //number of microsteps
|
#define E3_MICROSTEPS 16 //number of microsteps
|
||||||
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
|
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
|
||||||
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
|
||||||
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,40 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Configuration.h
|
||||||
|
*
|
||||||
|
* Basic settings such as:
|
||||||
|
*
|
||||||
|
* - Type of electronics
|
||||||
|
* - Type of temperature sensor
|
||||||
|
* - Printer geometry
|
||||||
|
* - Endstop configuration
|
||||||
|
* - LCD controller
|
||||||
|
* - Extra features
|
||||||
|
*
|
||||||
|
* Advanced settings can be found in Configuration_adv.h
|
||||||
|
*
|
||||||
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
|
@ -7,8 +44,10 @@
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
/*
|
|
||||||
Here are some standard links for getting your machine calibrated:
|
/**
|
||||||
|
* Here are some standard links for getting your machine calibrated:
|
||||||
|
*
|
||||||
* http://reprap.org/wiki/Calibration
|
* http://reprap.org/wiki/Calibration
|
||||||
* http://youtu.be/wAL9d7FgInk
|
* http://youtu.be/wAL9d7FgInk
|
||||||
* http://calculator.josefprusa.cz
|
* http://calculator.josefprusa.cz
|
||||||
|
@ -16,11 +55,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
* http://www.thingiverse.com/thing:5573
|
* http://www.thingiverse.com/thing:5573
|
||||||
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
|
||||||
* http://www.thingiverse.com/thing:298812
|
* http://www.thingiverse.com/thing:298812
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This configuration file contains the basic settings.
|
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= DELTA Printer ===============================
|
//============================= DELTA Printer ===============================
|
||||||
|
@ -70,7 +105,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// The following define selects which electronics board you have.
|
// The following define selects which electronics board you have.
|
||||||
// Please choose the name from boards.h that matches your setup
|
// Please choose the name from boards.h that matches your setup
|
||||||
#ifndef MOTHERBOARD
|
#ifndef MOTHERBOARD
|
||||||
#define MOTHERBOARD BOARD_RAMPS_13_EFB
|
#define MOTHERBOARD BOARD_RAMPS_14_EFB
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Optional custom name for your RepStrap or other custom machine
|
// Optional custom name for your RepStrap or other custom machine
|
||||||
|
@ -110,6 +145,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
||||||
//
|
//
|
||||||
//// Temperature sensor settings:
|
//// Temperature sensor settings:
|
||||||
|
// -3 is thermocouple with MAX31855 (only for sensor 0)
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
||||||
// -1 is thermocouple with AD595
|
// -1 is thermocouple with AD595
|
||||||
// 0 is not used
|
// 0 is not used
|
||||||
|
@ -129,6 +165,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
||||||
|
// 70 is the 100K thermistor found in the bq Hephestos 2
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
||||||
// (but gives greater accuracy and more stable PID)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -144,7 +181,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Use it for Testing or Development purposes. NEVER for production machine.
|
// Use it for Testing or Development purposes. NEVER for production machine.
|
||||||
//#define DUMMY_THERMISTOR_998_VALUE 25
|
//#define DUMMY_THERMISTOR_998_VALUE 25
|
||||||
//#define DUMMY_THERMISTOR_999_VALUE 100
|
//#define DUMMY_THERMISTOR_999_VALUE 100
|
||||||
// :{ '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" }
|
// :{ '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" }
|
||||||
#define TEMP_SENSOR_0 7
|
#define TEMP_SENSOR_0 7
|
||||||
#define TEMP_SENSOR_1 0
|
#define TEMP_SENSOR_1 0
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
|
@ -178,14 +215,9 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define HEATER_3_MAXTEMP 275
|
#define HEATER_3_MAXTEMP 275
|
||||||
#define BED_MAXTEMP 150
|
#define BED_MAXTEMP 150
|
||||||
|
|
||||||
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
|
|
||||||
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
|
|
||||||
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
|
|
||||||
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
|
|
||||||
|
|
||||||
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
|
||||||
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
|
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=U^2/R
|
||||||
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
|
//#define BED_WATTS (12.0*12.0/1.1) // P=U^2/R
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= PID Settings ================================
|
//============================= PID Settings ================================
|
||||||
|
@ -197,6 +229,7 @@ Here are some standard links for getting your machine calibrated:
|
||||||
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#if ENABLED(PIDTEMP)
|
#if ENABLED(PIDTEMP)
|
||||||
|
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#define PID_DEBUG // Sends debug data to the serial port.
|
||||||
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
//#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
|
//#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
|
||||||
|
@ -247,19 +280,19 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
|
||||||
|
|
||||||
#if ENABLED(PIDTEMPBED)
|
#if ENABLED(PIDTEMPBED)
|
||||||
|
|
||||||
|
//#define PID_BED_DEBUG // Sends debug data to the serial port.
|
||||||
|
|
||||||
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
||||||
#define DEFAULT_bedKp 10.00
|
#define DEFAULT_bedKp 10.00
|
||||||
#define DEFAULT_bedKi .023
|
#define DEFAULT_bedKi .023
|
||||||
#define DEFAULT_bedKd 305.4
|
#define DEFAULT_bedKd 305.4
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from pidautotune
|
//from pidautotune
|
||||||
//#define DEFAULT_bedKp 97.1
|
//#define DEFAULT_bedKp 97.1
|
||||||
//#define DEFAULT_bedKi 1.41
|
//#define DEFAULT_bedKi 1.41
|
||||||
|
@ -284,16 +317,15 @@ Here are some standard links for getting your machine calibrated:
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Runaway Protection protects your printer from damage and fire if a
|
* Thermal Protection protects your printer from damage and fire if a
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* thermistor falls out or temperature sensors fail in any way.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out or a temperature sensor fails,
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* Marlin can no longer sense the actual temperature. Since a disconnected
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long,
|
* details can be tuned in Configuration_adv.h
|
||||||
* the firmware will halt as a safety precaution.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders
|
||||||
|
@ -349,8 +381,22 @@ Here are some standard links for getting your machine calibrated:
|
||||||
// Enable this option for Toshiba steppers
|
// Enable this option for Toshiba steppers
|
||||||
//#define CONFIG_STEPPERS_TOSHIBA
|
//#define CONFIG_STEPPERS_TOSHIBA
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Endstop Settings ===========================
|
||||||
|
//===========================================================================
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
|
// Specify here all the endstop connectors that are connected to any endstop or probe.
|
||||||
|
// Almost all printers will be using one per axis. Probes will use one or more of the
|
||||||
|
// extra connectors. Leave undefined any used for non-endstop and non-probe purposes.
|
||||||
|
//#define USE_XMIN_PLUG
|
||||||
|
//#define USE_YMIN_PLUG
|
||||||
|
//#define USE_ZMIN_PLUG
|
||||||
|
#define USE_XMAX_PLUG
|
||||||
|
#define USE_YMAX_PLUG
|
||||||
|
#define USE_ZMAX_PLUG
|
||||||
|
|
||||||
// coarse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
|
@ -373,13 +419,53 @@ const bool X_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||||
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
||||||
//#define DISABLE_MAX_ENDSTOPS
|
|
||||||
//#define DISABLE_MIN_ENDSTOPS // Deltas only use min endstops for probing.
|
|
||||||
|
|
||||||
// If you want to enable the Z probe pin, but disable its use, uncomment the line below.
|
//===========================================================================
|
||||||
// This only affects a Z probe endstop if you have separate Z min endstop as well and have
|
//============================= Z Probe Options =============================
|
||||||
// activated Z_MIN_PROBE_ENDSTOP below. If you are using the Z Min endstop on your Z probe,
|
//===========================================================================
|
||||||
// this has no effect.
|
|
||||||
|
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
|
||||||
|
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
|
||||||
|
//
|
||||||
|
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
|
||||||
|
//
|
||||||
|
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
|
||||||
|
// Example: To park the head outside the bed area when homing with G28.
|
||||||
|
//
|
||||||
|
// To use a separate Z probe, your board must define a Z_MIN_PROBE_PIN.
|
||||||
|
//
|
||||||
|
// For a servo-based Z probe, you must set up servo support below, including
|
||||||
|
// NUM_SERVOS, Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES.
|
||||||
|
//
|
||||||
|
// - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin.
|
||||||
|
// - Use 5V for powered (usu. inductive) sensors.
|
||||||
|
// - Otherwise connect:
|
||||||
|
// - normally-closed switches to GND and D32.
|
||||||
|
// - normally-open switches to 5V and D32.
|
||||||
|
//
|
||||||
|
// Normally-closed switches are advised and are the default.
|
||||||
|
//
|
||||||
|
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
|
||||||
|
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
|
||||||
|
// default pin for all RAMPS-based boards. Some other boards map differently.
|
||||||
|
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
|
||||||
|
//
|
||||||
|
// WARNING:
|
||||||
|
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
|
||||||
|
// Use with caution and do your homework.
|
||||||
|
//
|
||||||
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
|
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
|
||||||
|
// The Z_MIN_PIN will then be used for both Z-homing and probing.
|
||||||
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
|
// To use a probe you must enable one of the two options above!
|
||||||
|
|
||||||
|
// This option disables the use of the Z_MIN_PROBE_PIN
|
||||||
|
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
|
||||||
|
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
|
||||||
|
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
|
||||||
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
|
@ -389,11 +475,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_ENABLE_ON 0
|
#define Z_ENABLE_ON 0
|
||||||
#define E_ENABLE_ON 0 // For all extruders
|
#define E_ENABLE_ON 0 // For all extruders
|
||||||
|
|
||||||
// Disables axis when it's not being used.
|
// Disables axis stepper immediately when it's not being used.
|
||||||
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
// WARNING: When motors turn off there is a chance of losing position accuracy!
|
||||||
#define DISABLE_X false
|
#define DISABLE_X false
|
||||||
#define DISABLE_Y false
|
#define DISABLE_Y false
|
||||||
#define DISABLE_Z false
|
#define DISABLE_Z false
|
||||||
|
// Warn on display about possibly reduced accuracy
|
||||||
|
//#define DISABLE_REDUCED_ACCURACY_WARNING
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
|
|
||||||
|
@ -416,6 +504,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define INVERT_E3_DIR false
|
#define INVERT_E3_DIR false
|
||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
//#define MIN_Z_HEIGHT_FOR_HOMING 15// (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
|
||||||
|
// Be sure you have this distance over your Z_MAX_POS in case.
|
||||||
|
|
||||||
// ENDSTOP SETTINGS:
|
// ENDSTOP SETTINGS:
|
||||||
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
// Sets direction of endstops when homing; 1=MAX, -1=MIN
|
||||||
|
@ -451,24 +541,26 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=========================== Manual Bed Leveling ===========================
|
//============================ Mesh Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
|
||||||
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
//#define MESH_BED_LEVELING // Enable mesh bed leveling.
|
||||||
|
|
||||||
#if ENABLED(MANUAL_BED_LEVELING)
|
|
||||||
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
|
||||||
#endif // MANUAL_BED_LEVELING
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
#define MESH_MIN_X 10
|
#define MESH_MIN_X 10
|
||||||
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
|
#define MESH_MAX_X (X_MAX_POS - (MESH_MIN_X))
|
||||||
#define MESH_MIN_Y 10
|
#define MESH_MIN_Y 10
|
||||||
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
|
#define MESH_MAX_Y (Y_MAX_POS - (MESH_MIN_Y))
|
||||||
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited.
|
||||||
#define MESH_NUM_Y_POINTS 3
|
#define MESH_NUM_Y_POINTS 3
|
||||||
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0.
|
||||||
|
|
||||||
|
//#define MANUAL_BED_LEVELING // Add display menu option for bed leveling.
|
||||||
|
|
||||||
|
#if ENABLED(MANUAL_BED_LEVELING)
|
||||||
|
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
|
||||||
|
#endif // MANUAL_BED_LEVELING
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -477,10 +569,9 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section bedlevel
|
// @section bedlevel
|
||||||
|
|
||||||
|
|
||||||
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
|
||||||
//#define DEBUG_LEVELING_FEATURE
|
//#define DEBUG_LEVELING_FEATURE
|
||||||
//#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
//#define Z_MIN_PROBE_REPEATABILITY_TEST // If not commented out, Z Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
|
||||||
|
|
||||||
|
@ -492,7 +583,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// This mode is preferred because there are more measurements.
|
// This mode is preferred because there are more measurements.
|
||||||
//
|
//
|
||||||
// - "3-point" mode
|
// - "3-point" mode
|
||||||
// Probe 3 arbitrary points on the bed (that aren't colinear)
|
// Probe 3 arbitrary points on the bed (that aren't collinear)
|
||||||
// You specify the XY coordinates of all 3 points.
|
// You specify the XY coordinates of all 3 points.
|
||||||
|
|
||||||
// Enable this to sample the bed in a grid (least squares solution).
|
// Enable this to sample the bed in a grid (least squares solution).
|
||||||
|
@ -502,41 +593,53 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#if ENABLED(AUTO_BED_LEVELING_GRID)
|
#if ENABLED(AUTO_BED_LEVELING_GRID)
|
||||||
|
|
||||||
// set the rectangle in which to probe
|
// set the rectangle in which to probe
|
||||||
#define DELTA_PROBABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
|
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
|
||||||
#define LEFT_PROBE_BED_POSITION -DELTA_PROBABLE_RADIUS
|
#define LEFT_PROBE_BED_POSITION -DELTA_PROBEABLE_RADIUS
|
||||||
#define RIGHT_PROBE_BED_POSITION DELTA_PROBABLE_RADIUS
|
#define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
|
||||||
#define FRONT_PROBE_BED_POSITION -DELTA_PROBABLE_RADIUS
|
#define FRONT_PROBE_BED_POSITION -DELTA_PROBEABLE_RADIUS
|
||||||
#define BACK_PROBE_BED_POSITION DELTA_PROBABLE_RADIUS
|
#define BACK_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
|
||||||
|
|
||||||
#define MIN_PROBE_EDGE 10 // The Z probe square sides can be no smaller than this.
|
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
|
||||||
|
|
||||||
// Non-linear bed leveling will be used.
|
// Non-linear bed leveling will be used.
|
||||||
// Compensate by interpolating between the nearest four Z probe values for each point.
|
// Compensate by interpolating between the nearest four Z probe values for each point.
|
||||||
// Useful for deltas where the print surface may appear like a bowl or dome shape.
|
// Useful for deltas where the print surface may appear like a bowl or dome shape.
|
||||||
// Works best with ACCURATE_BED_LEVELING_POINTS 5 or higher.
|
// Works best with AUTO_BED_LEVELING_GRID_POINTS 5 or higher.
|
||||||
#define AUTO_BED_LEVELING_GRID_POINTS 9
|
#define AUTO_BED_LEVELING_GRID_POINTS 9
|
||||||
|
|
||||||
#else // !AUTO_BED_LEVELING_GRID
|
#else // !AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Arbitrary points to probe.
|
// Arbitrary points to probe.
|
||||||
// A simple cross-product is used to estimate the plane of the bed.
|
// A simple cross-product is used to estimate the plane of the bed.
|
||||||
#define ABL_PROBE_PT_1_X 15
|
#define ABL_PROBE_PT_1_X 15
|
||||||
#define ABL_PROBE_PT_1_Y 180
|
#define ABL_PROBE_PT_1_Y 180
|
||||||
#define ABL_PROBE_PT_2_X 15
|
#define ABL_PROBE_PT_2_X 15
|
||||||
#define ABL_PROBE_PT_2_Y 20
|
#define ABL_PROBE_PT_2_Y 20
|
||||||
#define ABL_PROBE_PT_3_X 170
|
#define ABL_PROBE_PT_3_X 170
|
||||||
#define ABL_PROBE_PT_3_Y 20
|
#define ABL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_GRID
|
#endif // AUTO_BED_LEVELING_GRID
|
||||||
|
|
||||||
// Offsets to the Z probe relative to the nozzle tip.
|
// Z Probe to nozzle (X,Y) offset, relative to (0, 0).
|
||||||
// X and Y offsets must be integers.
|
// X and Y offsets must be integers.
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 0 // Z probe to nozzle X offset: -left +right
|
//
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -10 // Z probe to nozzle Y offset: -front +behind
|
// In the following example the X and Y offsets are both positive:
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -3.5 // Z probe to nozzle Z offset: -below (always!)
|
// #define X_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
|
// #define Y_PROBE_OFFSET_FROM_EXTRUDER 10
|
||||||
#define Z_RAISE_BEFORE_HOMING 15 // (in mm) Raise Z axis before homing (G28) for Z probe clearance.
|
//
|
||||||
// Be sure you have this distance over your Z_MAX_POS in case.
|
// +-- BACK ---+
|
||||||
|
// | |
|
||||||
|
// L | (+) P | R <-- probe (20,20)
|
||||||
|
// E | | I
|
||||||
|
// F | (-) N (+) | G <-- nozzle (10,10)
|
||||||
|
// T | | H
|
||||||
|
// | (-) | T
|
||||||
|
// | |
|
||||||
|
// O-- FRONT --+
|
||||||
|
// (0,0)
|
||||||
|
#define X_PROBE_OFFSET_FROM_EXTRUDER 0 // X offset: -left [of the nozzle] +right
|
||||||
|
#define Y_PROBE_OFFSET_FROM_EXTRUDER -10 // Y offset: -front [of the nozzle] +behind
|
||||||
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER -3.5 // Z offset: -below [the nozzle] (always negative!)
|
||||||
|
|
||||||
#define XY_TRAVEL_SPEED 4000 // X and Y axis travel speed between probes, in mm/min.
|
#define XY_TRAVEL_SPEED 4000 // X and Y axis travel speed between probes, in mm/min.
|
||||||
|
|
||||||
|
@ -544,13 +647,25 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points
|
#define Z_RAISE_BETWEEN_PROBINGS 5 // How much the Z axis will be raised when traveling from between next probing points
|
||||||
#define Z_RAISE_AFTER_PROBING 50 // How much the Z axis will be raised after the last probing point.
|
#define Z_RAISE_AFTER_PROBING 50 // How much the Z axis will be raised after the last probing point.
|
||||||
|
|
||||||
//#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.
|
//#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.
|
||||||
// Useful to retract a deployable Z probe.
|
// Useful to retract a deployable Z probe.
|
||||||
|
|
||||||
//#define Z_PROBE_SLED // Turn on if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
// Probes are sensors/switches that need to be activated before they can be used
|
||||||
|
// and deactivated after the use.
|
||||||
|
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, ... . You have to activate one of these for the AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
// A fix mounted probe, like the normal inductive probe, must be deactivated to go below Z_PROBE_OFFSET_FROM_EXTRUDER
|
||||||
|
// when the hardware endstops are active.
|
||||||
|
//#define FIX_MOUNTED_PROBE
|
||||||
|
|
||||||
|
// A Servo Probe can be defined in the servo section below.
|
||||||
|
|
||||||
|
// An Allen Key Probe is currently predefined only in the delta example configurations.
|
||||||
|
|
||||||
|
//#define Z_PROBE_SLED // Enable if you have a Z probe mounted on a sled like those designed by Charles Bell.
|
||||||
//#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.
|
//#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.
|
||||||
|
|
||||||
// Allen key retractable z-probe as seen on many Kossel delta printers - http://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe
|
// Allen key retractable Z probe as seen on many Kossel delta printers - http://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe
|
||||||
// Deploys by touching z-axis belt. Retracts by pushing the probe down. Uses Z_MIN_PIN.
|
// Deploys by touching z-axis belt. Retracts by pushing the probe down. Uses Z_MIN_PIN.
|
||||||
#define Z_PROBE_ALLEN_KEY
|
#define Z_PROBE_ALLEN_KEY
|
||||||
|
|
||||||
|
@ -635,10 +750,11 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE HOMING_FEEDRATE_XYZ
|
//#define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE HOMING_FEEDRATE_XYZ
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// If you have enabled the bed auto leveling and are using the same Z probe for Z homing,
|
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
|
||||||
// it is highly recommended you let this Z_SAFE_HOMING enabled!!!
|
// it is highly recommended you leave Z_SAFE_HOMING enabled!
|
||||||
|
|
||||||
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with Z probe outside the bed area.
|
#define Z_SAFE_HOMING // Use the z-min-probe for homing to z-min - not the z-min-endstop.
|
||||||
|
// This feature is meant to avoid Z homing with Z probe outside the bed area.
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled.
|
||||||
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
// - If stepper drivers timeout, it will need X and Y homing again before Z homing.
|
||||||
|
@ -652,37 +768,6 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Support for a dedicated Z probe endstop separate from the Z min endstop.
|
|
||||||
// If you would like to use both a Z probe and a Z min endstop together,
|
|
||||||
// uncomment #define Z_MIN_PROBE_ENDSTOP and read the instructions below.
|
|
||||||
// If you still want to use the Z min endstop for homing, disable Z_SAFE_HOMING above.
|
|
||||||
// Example: To park the head outside the bed area when homing with G28.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// The Z min endstop will need to set properly as it would without a Z probe
|
|
||||||
// to prevent head crashes and premature stopping during a print.
|
|
||||||
//
|
|
||||||
// To use a separate Z probe endstop, you must have a Z_MIN_PROBE_PIN
|
|
||||||
// defined in the pins_XXXXX.h file for your control board.
|
|
||||||
// If you are using a servo based Z probe, you will need to enable NUM_SERVOS,
|
|
||||||
// Z_ENDSTOP_SERVO_NR and SERVO_ENDSTOP_ANGLES in the R/C SERVO support below.
|
|
||||||
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin
|
|
||||||
// in the Aux 4 section of the RAMPS board. Use 5V for powered sensors,
|
|
||||||
// otherwise connect to ground and D32 for normally closed configuration
|
|
||||||
// and 5V and D32 for normally open configurations.
|
|
||||||
// Normally closed configuration is advised and assumed.
|
|
||||||
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin.
|
|
||||||
// Z_MIN_PROBE_PIN is setting the pin to use on the Arduino.
|
|
||||||
// Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
|
|
||||||
// D32 is currently selected in the RAMPS 1.3/1.4 pin file.
|
|
||||||
// All other boards will need changes to the respective pins_XXXXX.h file.
|
|
||||||
//
|
|
||||||
// WARNING:
|
|
||||||
// Setting the wrong pin may have unexpected and potentially disastrous outcomes.
|
|
||||||
// Use with caution and do your homework.
|
|
||||||
//
|
|
||||||
//#define Z_MIN_PROBE_ENDSTOP
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_FEATURE
|
#endif // AUTO_BED_LEVELING_FEATURE
|
||||||
|
|
||||||
|
|
||||||
|
@ -715,7 +800,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// delta speeds must be the same on xyz
|
// delta speeds must be the same on xyz
|
||||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {80, 80, 80, 760*1.1} // default steps per unit for Kossel (GT2, 20 tooth)
|
#define DEFAULT_AXIS_STEPS_PER_UNIT {80, 80, 80, 760*1.1} // default steps per unit for Kossel (GT2, 20 tooth)
|
||||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 500, 25} // (mm/sec)
|
#define DEFAULT_MAX_FEEDRATE {500, 500, 500, 25} // (mm/sec)
|
||||||
#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.
|
#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.
|
||||||
|
|
||||||
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
|
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
|
||||||
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
|
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
|
||||||
|
@ -758,6 +843,14 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
#define EEPROM_CHITCHAT // Please keep turned on if you can.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Host Keepalive
|
||||||
|
//
|
||||||
|
// By default Marlin will send a busy status message to the host
|
||||||
|
// every 10 seconds when it can't accept commands.
|
||||||
|
//
|
||||||
|
//#define DISABLE_HOST_KEEPALIVE // Enable this option if your host doesn't like keepalive messages.
|
||||||
|
|
||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
|
@ -778,13 +871,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// @section lcd
|
// @section lcd
|
||||||
|
|
||||||
// Define your display language below. Replace (en) with your language code and uncomment.
|
// Define your display language below. Replace (en) with your language code and uncomment.
|
||||||
// en, pl, fr, de, es, ru, bg, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
|
// 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
|
||||||
// See also language.h
|
// See also language.h
|
||||||
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
|
||||||
|
|
||||||
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
|
||||||
// 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.
|
// 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.
|
||||||
// See also documentation/LCDLanguageFont.md
|
// See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
|
||||||
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
|
||||||
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
//#define DISPLAY_CHARSET_HD44780_WESTERN
|
||||||
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
|
||||||
|
@ -792,12 +885,12 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define ULTRA_LCD //general LCD support, also 16x2
|
//#define ULTRA_LCD //general LCD support, also 16x2
|
||||||
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
|
||||||
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
|
||||||
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
// Changed behaviour! If you need SDSUPPORT uncomment it!
|
||||||
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
//#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)
|
||||||
//#define SDEXTRASLOW // Use even slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
|
|
||||||
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
|
||||||
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
|
||||||
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
|
||||||
|
//#define REVERSE_MENU_DIRECTION // When enabled CLOCKWISE moves UP in the LCD menu
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
|
||||||
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
//#define ULTIPANEL //the UltiPanel as on Thingiverse
|
||||||
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
//#define SPEAKER // The sound device is a speaker - not a buzzer. A buzzer resonates with his own frequency.
|
||||||
|
@ -814,13 +907,13 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
|
||||||
// http://panucatt.com
|
// http://panucatt.com
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define VIKI2
|
//#define VIKI2
|
||||||
//#define miniVIKI
|
//#define miniVIKI
|
||||||
|
|
||||||
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
// This is a new controller currently under development. https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
//#define ELB_FULL_GRAPHIC_CONTROLLER
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
|
@ -835,7 +928,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
|
||||||
//
|
//
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
|
|
||||||
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
|
||||||
|
@ -848,6 +941,10 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
||||||
//#define RA_CONTROL_PANEL
|
//#define RA_CONTROL_PANEL
|
||||||
|
|
||||||
|
// The MakerLab Mini Panel with graphic controller and SD support
|
||||||
|
// http://reprap.org/wiki/Mini_panel
|
||||||
|
//#define MINIPANEL
|
||||||
|
|
||||||
// Delta calibration menu
|
// Delta calibration menu
|
||||||
// uncomment to add three points calibration menu option.
|
// uncomment to add three points calibration menu option.
|
||||||
// See http://minow.blogspot.com/index.html#4918805519571907051
|
// See http://minow.blogspot.com/index.html#4918805519571907051
|
||||||
|
@ -861,6 +958,8 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
//#define LCD_I2C_SAINSMART_YWROBOT
|
//#define LCD_I2C_SAINSMART_YWROBOT
|
||||||
|
|
||||||
|
//#define LCM1602 // LCM1602 Adapter for 16x2 LCD
|
||||||
|
|
||||||
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
|
||||||
//
|
//
|
||||||
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
// This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
|
||||||
|
@ -874,7 +973,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
//#define LCD_I2C_VIKI
|
//#define LCD_I2C_VIKI
|
||||||
|
|
||||||
// SSD1306 OLED generic display support
|
// SSD1306 OLED generic display support
|
||||||
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
|
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: https://github.com/olikraus/U8glib_Arduino
|
||||||
//#define U8GLIB_SSD1306
|
//#define U8GLIB_SSD1306
|
||||||
|
|
||||||
// Shift register panels
|
// Shift register panels
|
||||||
|
@ -886,7 +985,7 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
//#define FAST_PWM_FAN
|
//#define FAST_PWM_FAN
|
||||||
|
|
||||||
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
@ -966,21 +1065,23 @@ const bool Z_MIN_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the l
|
||||||
* Note may require analog pins to be defined for different motherboards
|
* Note may require analog pins to be defined for different motherboards
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
// Uncomment below to enable
|
// Uncomment below to enable
|
||||||
//#define FILAMENT_SENSOR
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
|
||||||
|
|
||||||
#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
|
#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
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
|
||||||
#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)
|
|
||||||
|
|
||||||
//defines used in the code
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
|
||||||
|
|
||||||
//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.
|
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
|
||||||
|
#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)
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
|
||||||
|
|
||||||
|
//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.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Reference in a new issue