Merge latest bugfix-1.1.x
This commit is contained in:
12
.gitignore
vendored
12
.gitignore
vendored
@@ -118,19 +118,23 @@ tags
|
|||||||
|
|
||||||
# PlatformIO files/dirs
|
# PlatformIO files/dirs
|
||||||
.pio*
|
.pio*
|
||||||
|
.pioenvs
|
||||||
|
.piolibdeps
|
||||||
lib/readme.txt
|
lib/readme.txt
|
||||||
|
|
||||||
#Visual Studio
|
#Visual Studio
|
||||||
*.sln
|
*.sln
|
||||||
*.vcxproj
|
*.vcxproj
|
||||||
*.vcxproj.filters
|
*.vcxproj.filters
|
||||||
Marlin/Release/
|
Release/
|
||||||
Marlin/Debug/
|
Debug/
|
||||||
Marlin/__vm/
|
__vm/
|
||||||
Marlin/.vs/
|
.vs/
|
||||||
|
vc-fileutils.settings
|
||||||
|
|
||||||
#VScode
|
#VScode
|
||||||
.vscode
|
.vscode
|
||||||
|
.vscode/c_cpp_properties.json
|
||||||
|
|
||||||
#cmake
|
#cmake
|
||||||
CMakeLists.txt
|
CMakeLists.txt
|
||||||
|
|||||||
100
.travis.yml
100
.travis.yml
@@ -52,6 +52,10 @@ install:
|
|||||||
- git clone https://github.com/teemuatlut/TMC2130Stepper.git
|
- git clone https://github.com/teemuatlut/TMC2130Stepper.git
|
||||||
- sudo mv TMC2130Stepper /usr/local/share/arduino/libraries/TMC2130Stepper
|
- sudo mv TMC2130Stepper /usr/local/share/arduino/libraries/TMC2130Stepper
|
||||||
#
|
#
|
||||||
|
# Install: TMC2208 Stepper Motor Controller library
|
||||||
|
- git clone https://github.com/teemuatlut/TMC2208Stepper.git
|
||||||
|
- sudo mv TMC2208Stepper /usr/local/share/arduino/libraries/TMC2208Stepper
|
||||||
|
#
|
||||||
# Install: Adafruit Neopixel library
|
# Install: Adafruit Neopixel library
|
||||||
- git clone https://github.com/adafruit/Adafruit_NeoPixel.git
|
- git clone https://github.com/adafruit/Adafruit_NeoPixel.git
|
||||||
- sudo mv Adafruit_NeoPixel /usr/local/share/arduino/libraries/Adafruit_NeoPixel
|
- sudo mv Adafruit_NeoPixel /usr/local/share/arduino/libraries/Adafruit_NeoPixel
|
||||||
@@ -86,11 +90,11 @@ script:
|
|||||||
- opt_set TEMP_SENSOR_0 -2
|
- opt_set TEMP_SENSOR_0 -2
|
||||||
- opt_set TEMP_SENSOR_1 1
|
- opt_set TEMP_SENSOR_1 1
|
||||||
- opt_set TEMP_SENSOR_BED 1
|
- opt_set TEMP_SENSOR_BED 1
|
||||||
- opt_enable PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING ARC_P_CIRCLES CNC_WORKSPACE_PLANES
|
- opt_enable PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS
|
||||||
- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS
|
- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS
|
||||||
- opt_enable BLINKM PCA9632 RGB_LED NEOPIXEL_RGBW_LED
|
- opt_enable BLINKM PCA9632 RGB_LED NEOPIXEL_LED
|
||||||
- opt_enable AUTO_BED_LEVELING_LINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE
|
- opt_enable AUTO_BED_LEVELING_LINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE
|
||||||
- opt_enable_adv FWRETRACT MAX7219_DEBUG
|
- opt_enable_adv FWRETRACT MAX7219_DEBUG LED_CONTROL_MENU
|
||||||
- opt_set ABL_GRID_POINTS_X 16
|
- opt_set ABL_GRID_POINTS_X 16
|
||||||
- opt_set ABL_GRID_POINTS_Y 16
|
- opt_set ABL_GRID_POINTS_Y 16
|
||||||
- opt_set_adv FANMUX0_PIN 53
|
- opt_set_adv FANMUX0_PIN 53
|
||||||
@@ -99,20 +103,15 @@ script:
|
|||||||
# Test a probeless build of AUTO_BED_LEVELING_UBL
|
# Test a probeless build of AUTO_BED_LEVELING_UBL
|
||||||
#
|
#
|
||||||
- restore_configs
|
- restore_configs
|
||||||
- opt_enable AUTO_BED_LEVELING_UBL UBL_G26_MESH_EDITING ENABLE_LEVELING_FADE_HEIGHT EEPROM_SETTINGS G3D_PANEL
|
- opt_enable AUTO_BED_LEVELING_UBL DEBUG_LEVELING_FEATURE G26_MESH_EDITING ENABLE_LEVELING_FADE_HEIGHT EEPROM_SETTINGS EEPROM_CHITCHAT G3D_PANEL
|
||||||
- opt_enable_adv CUSTOM_USER_MENUS I2C_POSITION_ENCODERS BABYSTEPPING
|
- opt_enable_adv CUSTOM_USER_MENUS I2C_POSITION_ENCODERS BABYSTEPPING NANODLP_Z_SYNC
|
||||||
- build_marlin
|
- build_marlin
|
||||||
#
|
#
|
||||||
# And with a probe...
|
# Add a Sled Z Probe, use UBL Cartesian moves
|
||||||
#
|
#
|
||||||
- opt_enable FIX_MOUNTED_PROBE
|
- opt_enable Z_PROBE_SLED SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE
|
||||||
- build_marlin
|
- opt_disable SEGMENT_LEVELED_MOVES
|
||||||
#
|
- opt_enable_adv BABYSTEP_ZPROBE_OFFSET DOUBLECLICK_FOR_Z_BABYSTEPPING
|
||||||
# Test a Sled Z Probe
|
|
||||||
# ...with AUTO_BED_LEVELING_LINEAR, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, and EEPROM_CHITCHAT
|
|
||||||
#
|
|
||||||
- restore_configs
|
|
||||||
- opt_enable Z_PROBE_SLED AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT
|
|
||||||
- build_marlin
|
- build_marlin
|
||||||
#
|
#
|
||||||
# Test a Servo Probe
|
# Test a Servo Probe
|
||||||
@@ -122,23 +121,34 @@ script:
|
|||||||
- opt_enable NUM_SERVOS Z_ENDSTOP_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE
|
- opt_enable NUM_SERVOS Z_ENDSTOP_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
- opt_set NUM_SERVOS 1
|
- opt_set NUM_SERVOS 1
|
||||||
- opt_enable AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT
|
- opt_enable AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT
|
||||||
- opt_enable_adv EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET
|
- opt_enable_adv NO_VOLUMETRICS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET
|
||||||
- build_marlin
|
- build_marlin
|
||||||
#
|
#
|
||||||
# Test MESH_BED_LEVELING feature, with LCD
|
# Test MESH_BED_LEVELING feature, with LCD
|
||||||
#
|
#
|
||||||
- restore_configs
|
- restore_configs
|
||||||
- opt_enable MESH_BED_LEVELING MESH_G28_REST_ORIGIN LCD_BED_LEVELING ULTIMAKERCONTROLLER
|
- opt_enable MESH_BED_LEVELING G26_MESH_EDITING MESH_G28_REST_ORIGIN LCD_BED_LEVELING ULTIMAKERCONTROLLER
|
||||||
- build_marlin
|
- build_marlin
|
||||||
#
|
#
|
||||||
# Test PROBE_MANUALLY feature, with LCD support,
|
# Test MINIRAMBO for PWM_MOTOR_CURRENT
|
||||||
|
# PROBE_MANUALLY feature, with LCD support,
|
||||||
|
# ULTIMAKERCONTROLLER, FILAMENT_LCD_DISPLAY, FILAMENT_WIDTH_SENSOR,
|
||||||
|
# PRINTCOUNTER, NOZZLE_PARK_FEATURE, NOZZLE_CLEAN_FEATURE, PCA9632,
|
||||||
|
# Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS, BEZIER_CURVE_SUPPORT, EXPERIMENTAL_I2CBUS,
|
||||||
|
# ADVANCED_PAUSE_FEATURE, PARK_HEAD_ON_PAUSE, LCD_INFO_MENU,
|
||||||
# EEPROM_SETTINGS, EEPROM_CHITCHAT, M100_FREE_MEMORY_WATCHER,
|
# EEPROM_SETTINGS, EEPROM_CHITCHAT, M100_FREE_MEMORY_WATCHER,
|
||||||
# INCH_MODE_SUPPORT, TEMPERATURE_UNITS_SUPPORT
|
# INCH_MODE_SUPPORT, TEMPERATURE_UNITS_SUPPORT
|
||||||
#
|
#
|
||||||
- restore_configs
|
- restore_configs
|
||||||
- opt_set MOTHERBOARD BOARD_MINIRAMBO
|
- opt_set MOTHERBOARD BOARD_MINIRAMBO
|
||||||
- opt_enable PROBE_MANUALLY AUTO_BED_LEVELING_BILINEAR LCD_BED_LEVELING ULTIMAKERCONTROLLER
|
- opt_enable PROBE_MANUALLY AUTO_BED_LEVELING_BILINEAR G26_MESH_EDITING LCD_BED_LEVELING ULTIMAKERCONTROLLER
|
||||||
- opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT M100_FREE_MEMORY_WATCHER M100_FREE_MEMORY_DUMPER M100_FREE_MEMORY_CORRUPTOR INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT
|
- opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT M100_FREE_MEMORY_WATCHER M100_FREE_MEMORY_DUMPER M100_FREE_MEMORY_CORRUPTOR INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT
|
||||||
|
- opt_enable ULTIMAKERCONTROLLER SDSUPPORT
|
||||||
|
- opt_enable PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE PCA9632 USE_XMAX_PLUG
|
||||||
|
- opt_enable_adv BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS
|
||||||
|
- opt_enable_adv ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE LCD_INFO_MENU M114_DETAIL
|
||||||
|
- opt_set_adv PWM_MOTOR_CURRENT {1300,1300,1250}
|
||||||
|
- opt_set_adv I2C_SLAVE_ADDRESS 63
|
||||||
- build_marlin
|
- build_marlin
|
||||||
#
|
#
|
||||||
# Test 5 extruders on AZTEEG_X3_PRO (can use any board with >=5 extruders defined)
|
# Test 5 extruders on AZTEEG_X3_PRO (can use any board with >=5 extruders defined)
|
||||||
@@ -191,34 +201,29 @@ script:
|
|||||||
- opt_enable SWITCHING_EXTRUDER ULTIMAKERCONTROLLER
|
- opt_enable SWITCHING_EXTRUDER ULTIMAKERCONTROLLER
|
||||||
- build_marlin
|
- build_marlin
|
||||||
#
|
#
|
||||||
# Test MINIRAMBO for PWM_MOTOR_CURRENT
|
|
||||||
# ULTIMAKERCONTROLLER, FILAMENT_LCD_DISPLAY, FILAMENT_WIDTH_SENSOR,
|
|
||||||
# PRINTCOUNTER, NOZZLE_PARK_FEATURE, NOZZLE_CLEAN_FEATURE, PCA9632,
|
|
||||||
# Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS, BEZIER_CURVE_SUPPORT, EXPERIMENTAL_I2CBUS,
|
|
||||||
# ADVANCED_PAUSE_FEATURE, PARK_HEAD_ON_PAUSE, LCD_INFO_MENU,
|
|
||||||
#
|
|
||||||
- restore_configs
|
|
||||||
- opt_enable ULTIMAKERCONTROLLER FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR SDSUPPORT
|
|
||||||
- opt_enable PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE PCA9632
|
|
||||||
- opt_enable_adv Z_DUAL_STEPPER_DRIVERS Z_DUAL_ENDSTOPS BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS
|
|
||||||
- opt_set_adv I2C_SLAVE_ADDRESS 63
|
|
||||||
- opt_enable_adv ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE LCD_INFO_MENU
|
|
||||||
- pins_set RAMPS X_MAX_PIN -1
|
|
||||||
- opt_set_adv Z2_MAX_PIN 2
|
|
||||||
- build_marlin
|
|
||||||
#
|
|
||||||
# Enable COREXY
|
# Enable COREXY
|
||||||
#
|
#
|
||||||
- restore_configs
|
- restore_configs
|
||||||
- opt_enable COREXY
|
- opt_enable COREXY
|
||||||
- build_marlin
|
- build_marlin
|
||||||
#
|
#
|
||||||
# Enable COREYX (swapped)
|
# Test many less common options
|
||||||
#
|
|
||||||
#- restore_configs
|
|
||||||
#- opt_enable COREYX
|
|
||||||
#- build_marlin
|
|
||||||
#
|
#
|
||||||
|
- restore_configs
|
||||||
|
- opt_enable COREYX
|
||||||
|
- opt_set_adv FAN_MIN_PWM 50
|
||||||
|
- opt_set_adv FAN_KICKSTART_TIME 100
|
||||||
|
- opt_set_adv XY_FREQUENCY_LIMIT 15
|
||||||
|
- opt_enable_adv SHOW_TEMP_ADC_VALUES HOME_Y_BEFORE_X EMERGENCY_PARSER FAN_KICKSTART_TIME
|
||||||
|
- opt_enable_adv ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED ADVANCED_OK
|
||||||
|
- opt_enable_adv VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS ACTION_ON_KILL
|
||||||
|
- opt_enable_adv EXTRA_FAN_SPEED FWERETRACT Z_DUAL_STEPPER_DRIVERS Z_DUAL_ENDSTOPS
|
||||||
|
- opt_enable_adv MENU_ADDAUTOSTART SDCARD_SORT_ALPHA
|
||||||
|
- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||||
|
- opt_enable FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR
|
||||||
|
- opt_enable ENDSTOP_INTERRUPTS_FEATURE FAN_SOFT_PWM SDSUPPORT
|
||||||
|
- opt_enable USE_XMAX_PLUG
|
||||||
|
- build_marlin
|
||||||
#
|
#
|
||||||
######## Other Standard LCD/Panels ##############
|
######## Other Standard LCD/Panels ##############
|
||||||
#
|
#
|
||||||
@@ -252,7 +257,7 @@ script:
|
|||||||
#
|
#
|
||||||
- restore_configs
|
- restore_configs
|
||||||
- opt_enable G3D_PANEL SDSUPPORT
|
- opt_enable G3D_PANEL SDSUPPORT
|
||||||
- opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING
|
- opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING SCROLL_LONG_FILENAMES
|
||||||
- opt_set_adv SDSORT_GCODE true
|
- opt_set_adv SDSORT_GCODE true
|
||||||
- opt_set_adv SDSORT_USES_RAM true
|
- opt_set_adv SDSORT_USES_RAM true
|
||||||
- opt_set_adv SDSORT_USES_STACK true
|
- opt_set_adv SDSORT_USES_STACK true
|
||||||
@@ -263,7 +268,7 @@ script:
|
|||||||
#
|
#
|
||||||
- restore_configs
|
- restore_configs
|
||||||
- opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT
|
- opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT
|
||||||
- opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING
|
- opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING SCROLL_LONG_FILENAMES
|
||||||
- build_marlin
|
- build_marlin
|
||||||
#
|
#
|
||||||
# REPRAPWORLD_KEYPAD
|
# REPRAPWORLD_KEYPAD
|
||||||
@@ -326,7 +331,7 @@ script:
|
|||||||
#
|
#
|
||||||
- use_example_configs delta/generic
|
- use_example_configs delta/generic
|
||||||
- opt_disable DISABLE_MIN_ENDSTOPS
|
- opt_disable DISABLE_MIN_ENDSTOPS
|
||||||
- opt_enable AUTO_BED_LEVELING_UBL Z_PROBE_ALLEN_KEY EEPROM_SETTINGS EEPROM_CHITCHAT OLED_PANEL_TINYBOY2
|
- opt_enable AUTO_BED_LEVELING_UBL Z_PROBE_ALLEN_KEY EEPROM_SETTINGS EEPROM_CHITCHAT OLED_PANEL_TINYBOY2 MESH_EDIT_GFX_OVERLAY
|
||||||
- build_marlin
|
- build_marlin
|
||||||
#
|
#
|
||||||
# Delta Config (FLSUN AC because it's complex)
|
# Delta Config (FLSUN AC because it's complex)
|
||||||
@@ -344,7 +349,14 @@ script:
|
|||||||
- use_example_configs SCARA
|
- use_example_configs SCARA
|
||||||
- opt_enable AUTO_BED_LEVELING_BILINEAR FIX_MOUNTED_PROBE USE_ZMIN_PLUG EEPROM_SETTINGS EEPROM_CHITCHAT ULTIMAKERCONTROLLER
|
- opt_enable AUTO_BED_LEVELING_BILINEAR FIX_MOUNTED_PROBE USE_ZMIN_PLUG EEPROM_SETTINGS EEPROM_CHITCHAT ULTIMAKERCONTROLLER
|
||||||
- opt_enable_adv HAVE_TMC2130 X_IS_TMC2130 Y_IS_TMC2130 Z_IS_TMC2130
|
- opt_enable_adv HAVE_TMC2130 X_IS_TMC2130 Y_IS_TMC2130 Z_IS_TMC2130
|
||||||
- opt_enable_adv AUTOMATIC_CURRENT_CONTROL STEALTHCHOP HYBRID_THRESHOLD SENSORLESS_HOMING
|
- opt_enable_adv MONITOR_DRIVER_STATUS STEALTHCHOP HYBRID_THRESHOLD TMC_DEBUG SENSORLESS_HOMING
|
||||||
|
- build_marlin
|
||||||
|
#
|
||||||
|
# TMC2208 Config
|
||||||
|
#
|
||||||
|
- restore_configs
|
||||||
|
- opt_enable_adv HAVE_TMC2208 X_IS_TMC2208 Y_IS_TMC2208 Z_IS_TMC2208
|
||||||
|
- opt_enable_adv MONITOR_DRIVER_STATUS STEALTHCHOP HYBRID_THRESHOLD TMC_DEBUG
|
||||||
- build_marlin
|
- build_marlin
|
||||||
#
|
#
|
||||||
# tvrrug Config need to check board type for sanguino atmega644p
|
# tvrrug Config need to check board type for sanguino atmega644p
|
||||||
|
|||||||
@@ -42,7 +42,7 @@
|
|||||||
|
|
||||||
#define U8GLIB_ST7565_64128N
|
#define U8GLIB_ST7565_64128N
|
||||||
|
|
||||||
#elif ENABLED(ANET_KEYPAD_LCD)
|
#elif ENABLED(ZONESTAR_LCD)
|
||||||
|
|
||||||
#define REPRAPWORLD_KEYPAD
|
#define REPRAPWORLD_KEYPAD
|
||||||
#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
|
#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
|
||||||
@@ -53,6 +53,7 @@
|
|||||||
// this helps to implement ADC_KEYPAD menus
|
// this helps to implement ADC_KEYPAD menus
|
||||||
#define ENCODER_PULSES_PER_STEP 1
|
#define ENCODER_PULSES_PER_STEP 1
|
||||||
#define ENCODER_STEPS_PER_MENU_ITEM 1
|
#define ENCODER_STEPS_PER_MENU_ITEM 1
|
||||||
|
#define ENCODER_FEEDRATE_DEADZONE 2
|
||||||
#define REVERSE_MENU_DIRECTION
|
#define REVERSE_MENU_DIRECTION
|
||||||
|
|
||||||
#elif ENABLED(ANET_FULL_GRAPHICS_LCD)
|
#elif ENABLED(ANET_FULL_GRAPHICS_LCD)
|
||||||
@@ -62,7 +63,6 @@
|
|||||||
#elif ENABLED(BQ_LCD_SMART_CONTROLLER)
|
#elif ENABLED(BQ_LCD_SMART_CONTROLLER)
|
||||||
|
|
||||||
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
|
||||||
#define LONG_FILENAME_HOST_SUPPORT
|
|
||||||
|
|
||||||
#elif ENABLED(miniVIKI) || ENABLED(VIKI2) || ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
|
#elif ENABLED(miniVIKI) || ENABLED(VIKI2) || ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
|
||||||
|
|
||||||
@@ -125,6 +125,11 @@
|
|||||||
#define REPRAP_DISCOUNT_SMART_CONTROLLER
|
#define REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||||
#define U8GLIB_SH1106
|
#define U8GLIB_SH1106
|
||||||
|
|
||||||
|
#elif ENABLED(MKS_12864OLED_SSD1306)
|
||||||
|
|
||||||
|
#define REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||||
|
#define U8GLIB_SSD1306
|
||||||
|
|
||||||
#elif ENABLED(MKS_MINI_12864)
|
#elif ENABLED(MKS_MINI_12864)
|
||||||
|
|
||||||
#define MINIPANEL
|
#define MINIPANEL
|
||||||
@@ -155,7 +160,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) || ENABLED(LCD_FOR_MELZI)
|
#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) || ENABLED(LCD_FOR_MELZI) || ENABLED(SILVER_GATE_GLCD_CONTROLLER)
|
||||||
#define DOGLCD
|
#define DOGLCD
|
||||||
#define U8GLIB_ST7920
|
#define U8GLIB_ST7920
|
||||||
#define REPRAP_DISCOUNT_SMART_CONTROLLER
|
#define REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||||
@@ -306,7 +311,7 @@
|
|||||||
#define LCD_STR_FILAM_DIA "\xf8"
|
#define LCD_STR_FILAM_DIA "\xf8"
|
||||||
#define LCD_STR_FILAM_MUL "\xa4"
|
#define LCD_STR_FILAM_MUL "\xa4"
|
||||||
#else
|
#else
|
||||||
/* Custom characters defined in the first 8 characters of the LCD */
|
// Custom characters defined in the first 8 characters of the LCD
|
||||||
#define LCD_BEDTEMP_CHAR 0x00 // Print only as a char. This will have 'unexpected' results when used in a string!
|
#define LCD_BEDTEMP_CHAR 0x00 // Print only as a char. This will have 'unexpected' results when used in a string!
|
||||||
#define LCD_DEGREE_CHAR 0x01
|
#define LCD_DEGREE_CHAR 0x01
|
||||||
#define LCD_STR_THERMOMETER "\x02" // Still used with string concatenation
|
#define LCD_STR_THERMOMETER "\x02" // Still used with string concatenation
|
||||||
@@ -453,13 +458,6 @@
|
|||||||
*/
|
*/
|
||||||
#define HAS_Z_SERVO_ENDSTOP (defined(Z_ENDSTOP_SERVO_NR) && Z_ENDSTOP_SERVO_NR >= 0)
|
#define HAS_Z_SERVO_ENDSTOP (defined(Z_ENDSTOP_SERVO_NR) && Z_ENDSTOP_SERVO_NR >= 0)
|
||||||
|
|
||||||
/**
|
|
||||||
* UBL has its own manual probing, so this just causes trouble.
|
|
||||||
*/
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#undef PROBE_MANUALLY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Set a flag for any enabled probe
|
* Set a flag for any enabled probe
|
||||||
*/
|
*/
|
||||||
|
|||||||
@@ -89,7 +89,7 @@
|
|||||||
#define CORE_AXIS_1 B_AXIS
|
#define CORE_AXIS_1 B_AXIS
|
||||||
#define CORE_AXIS_2 C_AXIS
|
#define CORE_AXIS_2 C_AXIS
|
||||||
#endif
|
#endif
|
||||||
#if (ENABLED(COREYX) || ENABLED(COREZX) || ENABLED(COREZY))
|
#if ENABLED(COREYX) || ENABLED(COREZX) || ENABLED(COREZY)
|
||||||
#define CORESIGN(n) (-(n))
|
#define CORESIGN(n) (-(n))
|
||||||
#else
|
#else
|
||||||
#define CORESIGN(n) (n)
|
#define CORESIGN(n) (n)
|
||||||
@@ -378,29 +378,122 @@
|
|||||||
#define ARRAY_BY_HOTENDS(...) ARRAY_N(HOTENDS, __VA_ARGS__)
|
#define ARRAY_BY_HOTENDS(...) ARRAY_N(HOTENDS, __VA_ARGS__)
|
||||||
#define ARRAY_BY_HOTENDS1(v1) ARRAY_BY_HOTENDS(v1, v1, v1, v1, v1, v1)
|
#define ARRAY_BY_HOTENDS1(v1) ARRAY_BY_HOTENDS(v1, v1, v1, v1, v1, v1)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* X_DUAL_ENDSTOPS endstop reassignment
|
||||||
|
*/
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#if X_HOME_DIR > 0
|
||||||
|
#if X2_USE_ENDSTOP == _XMIN_
|
||||||
|
#define X2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
|
||||||
|
#define X2_MAX_PIN X_MIN_PIN
|
||||||
|
#elif X2_USE_ENDSTOP == _XMAX_
|
||||||
|
#define X2_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
|
||||||
|
#define X2_MAX_PIN X_MAX_PIN
|
||||||
|
#elif X2_USE_ENDSTOP == _YMIN_
|
||||||
|
#define X2_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
|
||||||
|
#define X2_MAX_PIN Y_MIN_PIN
|
||||||
|
#elif X2_USE_ENDSTOP == _YMAX_
|
||||||
|
#define X2_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
|
||||||
|
#define X2_MAX_PIN Y_MAX_PIN
|
||||||
|
#elif X2_USE_ENDSTOP == _ZMIN_
|
||||||
|
#define X2_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
|
||||||
|
#define X2_MAX_PIN Z_MIN_PIN
|
||||||
|
#elif X2_USE_ENDSTOP == _ZMAX_
|
||||||
|
#define X2_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
|
||||||
|
#define X2_MAX_PIN Z_MAX_PIN
|
||||||
|
#else
|
||||||
|
#define X2_MAX_ENDSTOP_INVERTING false
|
||||||
|
#endif
|
||||||
|
#define X2_MIN_ENDSTOP_INVERTING false
|
||||||
|
#else
|
||||||
|
#if X2_USE_ENDSTOP == _XMIN_
|
||||||
|
#define X2_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
|
||||||
|
#define X2_MIN_PIN X_MIN_PIN
|
||||||
|
#elif X2_USE_ENDSTOP == _XMAX_
|
||||||
|
#define X2_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
|
||||||
|
#define X2_MIN_PIN X_MAX_PIN
|
||||||
|
#elif X2_USE_ENDSTOP == _YMIN_
|
||||||
|
#define X2_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
|
||||||
|
#define X2_MIN_PIN Y_MIN_PIN
|
||||||
|
#elif X2_USE_ENDSTOP == _YMAX_
|
||||||
|
#define X2_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
|
||||||
|
#define X2_MIN_PIN Y_MAX_PIN
|
||||||
|
#elif X2_USE_ENDSTOP == _ZMIN_
|
||||||
|
#define X2_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
|
||||||
|
#define X2_MIN_PIN Z_MIN_PIN
|
||||||
|
#elif X2_USE_ENDSTOP == _ZMAX_
|
||||||
|
#define X2_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
|
||||||
|
#define X2_MIN_PIN Z_MAX_PIN
|
||||||
|
#else
|
||||||
|
#define X2_MIN_ENDSTOP_INVERTING false
|
||||||
|
#endif
|
||||||
|
#define X2_MAX_ENDSTOP_INVERTING false
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Is an endstop plug used for the X2 endstop?
|
||||||
|
#define IS_X2_ENDSTOP(A,M) (ENABLED(X_DUAL_ENDSTOPS) && X2_USE_ENDSTOP == _##A##M##_)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Y_DUAL_ENDSTOPS endstop reassignment
|
||||||
|
*/
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#if Y_HOME_DIR > 0
|
||||||
|
#if Y2_USE_ENDSTOP == _XMIN_
|
||||||
|
#define Y2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
|
||||||
|
#define Y2_MAX_PIN X_MIN_PIN
|
||||||
|
#elif Y2_USE_ENDSTOP == _XMAX_
|
||||||
|
#define Y2_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
|
||||||
|
#define Y2_MAX_PIN X_MAX_PIN
|
||||||
|
#elif Y2_USE_ENDSTOP == _YMIN_
|
||||||
|
#define Y2_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
|
||||||
|
#define Y2_MAX_PIN Y_MIN_PIN
|
||||||
|
#elif Y2_USE_ENDSTOP == _YMAX_
|
||||||
|
#define Y2_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
|
||||||
|
#define Y2_MAX_PIN Y_MAX_PIN
|
||||||
|
#elif Y2_USE_ENDSTOP == _ZMIN_
|
||||||
|
#define Y2_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
|
||||||
|
#define Y2_MAX_PIN Z_MIN_PIN
|
||||||
|
#elif Y2_USE_ENDSTOP == _ZMAX_
|
||||||
|
#define Y2_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
|
||||||
|
#define Y2_MAX_PIN Z_MAX_PIN
|
||||||
|
#else
|
||||||
|
#define Y2_MAX_ENDSTOP_INVERTING false
|
||||||
|
#endif
|
||||||
|
#define Y2_MIN_ENDSTOP_INVERTING false
|
||||||
|
#else
|
||||||
|
#if Y2_USE_ENDSTOP == _XMIN_
|
||||||
|
#define Y2_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
|
||||||
|
#define Y2_MIN_PIN X_MIN_PIN
|
||||||
|
#elif Y2_USE_ENDSTOP == _XMAX_
|
||||||
|
#define Y2_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
|
||||||
|
#define Y2_MIN_PIN X_MAX_PIN
|
||||||
|
#elif Y2_USE_ENDSTOP == _YMIN_
|
||||||
|
#define Y2_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
|
||||||
|
#define Y2_MIN_PIN Y_MIN_PIN
|
||||||
|
#elif Y2_USE_ENDSTOP == _YMAX_
|
||||||
|
#define Y2_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
|
||||||
|
#define Y2_MIN_PIN Y_MAX_PIN
|
||||||
|
#elif Y2_USE_ENDSTOP == _ZMIN_
|
||||||
|
#define Y2_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
|
||||||
|
#define Y2_MIN_PIN Z_MIN_PIN
|
||||||
|
#elif Y2_USE_ENDSTOP == _ZMAX_
|
||||||
|
#define Y2_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
|
||||||
|
#define Y2_MIN_PIN Z_MAX_PIN
|
||||||
|
#else
|
||||||
|
#define Y2_MIN_ENDSTOP_INVERTING false
|
||||||
|
#endif
|
||||||
|
#define Y2_MAX_ENDSTOP_INVERTING false
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Is an endstop plug used for the Y2 endstop or the bed probe?
|
||||||
|
#define IS_Y2_ENDSTOP(A,M) (ENABLED(Y_DUAL_ENDSTOPS) && Y2_USE_ENDSTOP == _##A##M##_)
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z_DUAL_ENDSTOPS endstop reassignment
|
* Z_DUAL_ENDSTOPS endstop reassignment
|
||||||
*/
|
*/
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define _XMIN_ 100
|
|
||||||
#define _YMIN_ 200
|
|
||||||
#define _ZMIN_ 300
|
|
||||||
#define _XMAX_ 101
|
|
||||||
#define _YMAX_ 201
|
|
||||||
#define _ZMAX_ 301
|
|
||||||
#if Z2_USE_ENDSTOP == _XMIN_
|
|
||||||
#define USE_XMIN_PLUG
|
|
||||||
#elif Z2_USE_ENDSTOP == _XMAX_
|
|
||||||
#define USE_XMAX_PLUG
|
|
||||||
#elif Z2_USE_ENDSTOP == _YMIN_
|
|
||||||
#define USE_YMIN_PLUG
|
|
||||||
#elif Z2_USE_ENDSTOP == _YMAX_
|
|
||||||
#define USE_YMAX_PLUG
|
|
||||||
#elif Z2_USE_ENDSTOP == _ZMIN_
|
|
||||||
#define USE_ZMIN_PLUG
|
|
||||||
#elif Z2_USE_ENDSTOP == _ZMAX_
|
|
||||||
#define USE_ZMAX_PLUG
|
|
||||||
#endif
|
|
||||||
#if Z_HOME_DIR > 0
|
#if Z_HOME_DIR > 0
|
||||||
#if Z2_USE_ENDSTOP == _XMIN_
|
#if Z2_USE_ENDSTOP == _XMIN_
|
||||||
#define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
|
#define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
|
||||||
@@ -423,6 +516,7 @@
|
|||||||
#else
|
#else
|
||||||
#define Z2_MAX_ENDSTOP_INVERTING false
|
#define Z2_MAX_ENDSTOP_INVERTING false
|
||||||
#endif
|
#endif
|
||||||
|
#define Z2_MIN_ENDSTOP_INVERTING false
|
||||||
#else
|
#else
|
||||||
#if Z2_USE_ENDSTOP == _XMIN_
|
#if Z2_USE_ENDSTOP == _XMIN_
|
||||||
#define Z2_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
|
#define Z2_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
|
||||||
@@ -445,6 +539,7 @@
|
|||||||
#else
|
#else
|
||||||
#define Z2_MIN_ENDSTOP_INVERTING false
|
#define Z2_MIN_ENDSTOP_INVERTING false
|
||||||
#endif
|
#endif
|
||||||
|
#define Z2_MAX_ENDSTOP_INVERTING false
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -541,12 +636,16 @@
|
|||||||
#define HAS_SOLENOID_4 (PIN_EXISTS(SOL4))
|
#define HAS_SOLENOID_4 (PIN_EXISTS(SOL4))
|
||||||
|
|
||||||
// Endstops and bed probe
|
// Endstops and bed probe
|
||||||
#define HAS_X_MIN (PIN_EXISTS(X_MIN) && !IS_Z2_OR_PROBE(X,MIN))
|
#define HAS_X_MIN (PIN_EXISTS(X_MIN) && !IS_X2_ENDSTOP(X,MIN) && !IS_Y2_ENDSTOP(X,MIN) && !IS_Z2_OR_PROBE(X,MIN))
|
||||||
#define HAS_X_MAX (PIN_EXISTS(X_MAX) && !IS_Z2_OR_PROBE(X,MAX))
|
#define HAS_X_MAX (PIN_EXISTS(X_MAX) && !IS_X2_ENDSTOP(X,MAX) && !IS_Y2_ENDSTOP(X,MAX) && !IS_Z2_OR_PROBE(X,MAX))
|
||||||
#define HAS_Y_MIN (PIN_EXISTS(Y_MIN) && !IS_Z2_OR_PROBE(Y,MIN))
|
#define HAS_Y_MIN (PIN_EXISTS(Y_MIN) && !IS_X2_ENDSTOP(Y,MIN) && !IS_Y2_ENDSTOP(Y,MIN) && !IS_Z2_OR_PROBE(Y,MIN))
|
||||||
#define HAS_Y_MAX (PIN_EXISTS(Y_MAX) && !IS_Z2_OR_PROBE(Y,MAX))
|
#define HAS_Y_MAX (PIN_EXISTS(Y_MAX) && !IS_X2_ENDSTOP(Y,MAX) && !IS_Y2_ENDSTOP(Y,MAX) && !IS_Z2_OR_PROBE(Y,MAX))
|
||||||
#define HAS_Z_MIN (PIN_EXISTS(Z_MIN) && !IS_Z2_OR_PROBE(Z,MIN))
|
#define HAS_Z_MIN (PIN_EXISTS(Z_MIN) && !IS_X2_ENDSTOP(Z,MIN) && !IS_Y2_ENDSTOP(Z,MIN) && !IS_Z2_OR_PROBE(Z,MIN))
|
||||||
#define HAS_Z_MAX (PIN_EXISTS(Z_MAX) && !IS_Z2_OR_PROBE(Z,MAX))
|
#define HAS_Z_MAX (PIN_EXISTS(Z_MAX) && !IS_X2_ENDSTOP(Z,MAX) && !IS_Y2_ENDSTOP(Z,MAX) && !IS_Z2_OR_PROBE(Z,MAX))
|
||||||
|
#define HAS_X2_MIN (PIN_EXISTS(X2_MIN))
|
||||||
|
#define HAS_X2_MAX (PIN_EXISTS(X2_MAX))
|
||||||
|
#define HAS_Y2_MIN (PIN_EXISTS(Y2_MIN))
|
||||||
|
#define HAS_Y2_MAX (PIN_EXISTS(Y2_MAX))
|
||||||
#define HAS_Z2_MIN (PIN_EXISTS(Z2_MIN))
|
#define HAS_Z2_MIN (PIN_EXISTS(Z2_MIN))
|
||||||
#define HAS_Z2_MAX (PIN_EXISTS(Z2_MAX))
|
#define HAS_Z2_MAX (PIN_EXISTS(Z2_MAX))
|
||||||
#define HAS_Z_MIN_PROBE_PIN (PIN_EXISTS(Z_MIN_PROBE))
|
#define HAS_Z_MIN_PROBE_PIN (PIN_EXISTS(Z_MIN_PROBE))
|
||||||
@@ -705,8 +804,7 @@
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define PROBE_PIN_CONFIGURED (HAS_Z_MIN_PROBE_PIN || (HAS_Z_MIN && ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)))
|
#define HAS_BED_PROBE (PROBE_SELECTED && DISABLED(PROBE_MANUALLY))
|
||||||
#define HAS_BED_PROBE (PROBE_SELECTED && PROBE_PIN_CONFIGURED && DISABLED(PROBE_MANUALLY))
|
|
||||||
|
|
||||||
#if ENABLED(Z_PROBE_ALLEN_KEY)
|
#if ENABLED(Z_PROBE_ALLEN_KEY)
|
||||||
#define PROBE_IS_TRIGGERED_WHEN_STOWED_TEST
|
#define PROBE_IS_TRIGGERED_WHEN_STOWED_TEST
|
||||||
@@ -746,6 +844,49 @@
|
|||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER 0
|
#define Z_PROBE_OFFSET_FROM_EXTRUDER 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* XYZ Bed Skew Correction
|
||||||
|
*/
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
#define SKEW_FACTOR_MIN -1
|
||||||
|
#define SKEW_FACTOR_MAX 1
|
||||||
|
|
||||||
|
#define _GET_SIDE(a,b,c) (SQRT(2*sq(a)+2*sq(b)-4*sq(c))*0.5)
|
||||||
|
#define _SKEW_SIDE(a,b,c) tan(M_PI*0.5-acos((sq(a)-sq(b)-sq(c))/(2*c*b)))
|
||||||
|
#define _SKEW_FACTOR(a,b,c) _SKEW_SIDE(a,_GET_SIDE(a,b,c),c)
|
||||||
|
|
||||||
|
#ifndef XY_SKEW_FACTOR
|
||||||
|
constexpr float XY_SKEW_FACTOR = (
|
||||||
|
#if defined(XY_DIAG_AC) && defined(XY_DIAG_BD) && defined(XY_SIDE_AD)
|
||||||
|
_SKEW_FACTOR(XY_DIAG_AC, XY_DIAG_BD, XY_SIDE_AD)
|
||||||
|
#else
|
||||||
|
0.0
|
||||||
|
#endif
|
||||||
|
);
|
||||||
|
#endif
|
||||||
|
#ifndef XZ_SKEW_FACTOR
|
||||||
|
#if defined(XY_SIDE_AD) && !defined(XZ_SIDE_AD)
|
||||||
|
#define XZ_SIDE_AD XY_SIDE_AD
|
||||||
|
#endif
|
||||||
|
constexpr float XZ_SKEW_FACTOR = (
|
||||||
|
#if defined(XZ_DIAG_AC) && defined(XZ_DIAG_BD) && defined(XZ_SIDE_AD)
|
||||||
|
_SKEW_FACTOR(XZ_DIAG_AC, XZ_DIAG_BD, XZ_SIDE_AD)
|
||||||
|
#else
|
||||||
|
0.0
|
||||||
|
#endif
|
||||||
|
);
|
||||||
|
#endif
|
||||||
|
#ifndef YZ_SKEW_FACTOR
|
||||||
|
constexpr float YZ_SKEW_FACTOR = (
|
||||||
|
#if defined(YZ_DIAG_AC) && defined(YZ_DIAG_BD) && defined(YZ_SIDE_AD)
|
||||||
|
_SKEW_FACTOR(YZ_DIAG_AC, YZ_DIAG_BD, YZ_SIDE_AD)
|
||||||
|
#else
|
||||||
|
0.0
|
||||||
|
#endif
|
||||||
|
);
|
||||||
|
#endif
|
||||||
|
#endif // SKEW_CORRECTION
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Heater & Fan Pausing
|
* Heater & Fan Pausing
|
||||||
*/
|
*/
|
||||||
@@ -755,10 +896,23 @@
|
|||||||
#define QUIET_PROBING (HAS_BED_PROBE && (ENABLED(PROBING_HEATERS_OFF) || ENABLED(PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0))
|
#define QUIET_PROBING (HAS_BED_PROBE && (ENABLED(PROBING_HEATERS_OFF) || ENABLED(PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0))
|
||||||
#define HEATER_IDLE_HANDLER (ENABLED(ADVANCED_PAUSE_FEATURE) || ENABLED(PROBING_HEATERS_OFF))
|
#define HEATER_IDLE_HANDLER (ENABLED(ADVANCED_PAUSE_FEATURE) || ENABLED(PROBING_HEATERS_OFF))
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Only constrain Z on DELTA / SCARA machines
|
||||||
|
*/
|
||||||
|
#if IS_KINEMATIC
|
||||||
|
#undef MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#undef MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#undef MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#undef MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Delta radius/rod trimmers/angle trimmers
|
* Delta radius/rod trimmers/angle trimmers
|
||||||
*/
|
*/
|
||||||
#if ENABLED(DELTA)
|
#if ENABLED(DELTA)
|
||||||
|
#ifndef DELTA_PROBEABLE_RADIUS
|
||||||
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
|
#endif
|
||||||
#ifndef DELTA_CALIBRATION_RADIUS
|
#ifndef DELTA_CALIBRATION_RADIUS
|
||||||
#define DELTA_CALIBRATION_RADIUS DELTA_PRINTABLE_RADIUS - 10
|
#define DELTA_CALIBRATION_RADIUS DELTA_PRINTABLE_RADIUS - 10
|
||||||
#endif
|
#endif
|
||||||
@@ -779,19 +933,103 @@
|
|||||||
/**
|
/**
|
||||||
* Set granular options based on the specific type of leveling
|
* Set granular options based on the specific type of leveling
|
||||||
*/
|
*/
|
||||||
|
#define UBL_SEGMENTED (ENABLED(AUTO_BED_LEVELING_UBL) && (ENABLED(DELTA) || ENABLED(SEGMENT_LEVELED_MOVES)))
|
||||||
#define UBL_DELTA (ENABLED(AUTO_BED_LEVELING_UBL) && (ENABLED(DELTA) || ENABLED(UBL_GRANULAR_SEGMENTATION_FOR_CARTESIAN)))
|
|
||||||
#define ABL_PLANAR (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_3POINT))
|
#define ABL_PLANAR (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_3POINT))
|
||||||
#define ABL_GRID (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR))
|
#define ABL_GRID (ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR))
|
||||||
#define HAS_ABL (ABL_PLANAR || ABL_GRID || ENABLED(AUTO_BED_LEVELING_UBL))
|
#define OLDSCHOOL_ABL (ABL_PLANAR || ABL_GRID)
|
||||||
|
#define HAS_ABL (OLDSCHOOL_ABL || ENABLED(AUTO_BED_LEVELING_UBL))
|
||||||
#define HAS_LEVELING (HAS_ABL || ENABLED(MESH_BED_LEVELING))
|
#define HAS_LEVELING (HAS_ABL || ENABLED(MESH_BED_LEVELING))
|
||||||
#define PLANNER_LEVELING (ABL_PLANAR || ABL_GRID || ENABLED(MESH_BED_LEVELING) || UBL_DELTA)
|
#define HAS_AUTOLEVEL (HAS_ABL && DISABLED(PROBE_MANUALLY))
|
||||||
|
#define HAS_MESH (ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(MESH_BED_LEVELING))
|
||||||
|
#define PLANNER_LEVELING (OLDSCHOOL_ABL || ENABLED(MESH_BED_LEVELING) || UBL_SEGMENTED || ENABLED(SKEW_CORRECTION))
|
||||||
#define HAS_PROBING_PROCEDURE (HAS_ABL || ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST))
|
#define HAS_PROBING_PROCEDURE (HAS_ABL || ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST))
|
||||||
#if HAS_PROBING_PROCEDURE
|
#if HAS_PROBING_PROCEDURE
|
||||||
#define PROBE_BED_WIDTH abs(RIGHT_PROBE_BED_POSITION - (LEFT_PROBE_BED_POSITION))
|
#define PROBE_BED_WIDTH abs(RIGHT_PROBE_BED_POSITION - (LEFT_PROBE_BED_POSITION))
|
||||||
#define PROBE_BED_HEIGHT abs(BACK_PROBE_BED_POSITION - (FRONT_PROBE_BED_POSITION))
|
#define PROBE_BED_HEIGHT abs(BACK_PROBE_BED_POSITION - (FRONT_PROBE_BED_POSITION))
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(SEGMENT_LEVELED_MOVES) && !defined(LEVELED_SEGMENT_LENGTH)
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Probing rectangular bounds
|
||||||
|
* These can be further constrained in code for Delta and SCARA
|
||||||
|
*/
|
||||||
|
#if ENABLED(DELTA)
|
||||||
|
// Probing points may be verified at compile time within the radius
|
||||||
|
// using static_assert(HYPOT2(X2-X1,Y2-Y1)<=sq(DELTA_PRINTABLE_RADIUS),"bad probe point!")
|
||||||
|
// so that may be added to SanityCheck.h in the future.
|
||||||
|
#define _MIN_PROBE_X (X_CENTER - DELTA_PRINTABLE_RADIUS)
|
||||||
|
#define _MIN_PROBE_Y (Y_CENTER - DELTA_PRINTABLE_RADIUS)
|
||||||
|
#define _MAX_PROBE_X (X_CENTER + DELTA_PRINTABLE_RADIUS)
|
||||||
|
#define _MAX_PROBE_Y (Y_CENTER + DELTA_PRINTABLE_RADIUS)
|
||||||
|
#elif IS_SCARA
|
||||||
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
|
#define _MIN_PROBE_X (X_CENTER - (SCARA_PRINTABLE_RADIUS))
|
||||||
|
#define _MIN_PROBE_Y (Y_CENTER - (SCARA_PRINTABLE_RADIUS))
|
||||||
|
#define _MAX_PROBE_X (X_CENTER + SCARA_PRINTABLE_RADIUS)
|
||||||
|
#define _MAX_PROBE_Y (Y_CENTER + SCARA_PRINTABLE_RADIUS)
|
||||||
|
#else
|
||||||
|
// Boundaries for Cartesian probing based on bed limits
|
||||||
|
#define _MIN_PROBE_X (max(X_MIN_BED, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
|
||||||
|
#define _MIN_PROBE_Y (max(Y_MIN_BED, Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
|
||||||
|
#define _MAX_PROBE_X (min(X_MAX_BED, X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
|
||||||
|
#define _MAX_PROBE_Y (min(Y_MAX_BED, Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Allow configuration to override these for special purposes
|
||||||
|
#ifndef MIN_PROBE_X
|
||||||
|
#define MIN_PROBE_X _MIN_PROBE_X
|
||||||
|
#endif
|
||||||
|
#ifndef MIN_PROBE_Y
|
||||||
|
#define MIN_PROBE_Y _MIN_PROBE_Y
|
||||||
|
#endif
|
||||||
|
#ifndef MAX_PROBE_X
|
||||||
|
#define MAX_PROBE_X _MAX_PROBE_X
|
||||||
|
#endif
|
||||||
|
#ifndef MAX_PROBE_Y
|
||||||
|
#define MAX_PROBE_Y _MAX_PROBE_Y
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Default mesh area is an area with an inset margin on the print area.
|
||||||
|
*/
|
||||||
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
#if IS_KINEMATIC
|
||||||
|
// Probing points may be verified at compile time within the radius
|
||||||
|
// using static_assert(HYPOT2(X2-X1,Y2-Y1)<=sq(DELTA_PRINTABLE_RADIUS),"bad probe point!")
|
||||||
|
// so that may be added to SanityCheck.h in the future.
|
||||||
|
#define _MESH_MIN_X (MIN_PROBE_X + MESH_INSET)
|
||||||
|
#define _MESH_MIN_Y (MIN_PROBE_Y + MESH_INSET)
|
||||||
|
#define _MESH_MAX_X (MAX_PROBE_X - (MESH_INSET))
|
||||||
|
#define _MESH_MAX_Y (MAX_PROBE_Y - (MESH_INSET))
|
||||||
|
#else
|
||||||
|
// Boundaries for Cartesian probing based on set limits
|
||||||
|
#define _MESH_MIN_X (max(X_MIN_BED + MESH_INSET, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
|
||||||
|
#define _MESH_MIN_Y (max(Y_MIN_BED + MESH_INSET, Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
|
||||||
|
#define _MESH_MAX_X (min(X_MAX_BED - (MESH_INSET), X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
|
||||||
|
#define _MESH_MAX_Y (min(Y_MAX_BED - (MESH_INSET), Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
|
||||||
|
#endif
|
||||||
|
/**
|
||||||
|
* These may be overridden in Configuration if a smaller area is wanted
|
||||||
|
*/
|
||||||
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
#ifndef MESH_MIN_X
|
||||||
|
#define MESH_MIN_X _MESH_MIN_X
|
||||||
|
#endif
|
||||||
|
#ifndef MESH_MIN_Y
|
||||||
|
#define MESH_MIN_Y _MESH_MIN_Y
|
||||||
|
#endif
|
||||||
|
#ifndef MESH_MAX_X
|
||||||
|
#define MESH_MAX_X _MESH_MAX_X
|
||||||
|
#endif
|
||||||
|
#ifndef MESH_MAX_Y
|
||||||
|
#define MESH_MAX_Y _MESH_MAX_Y
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#endif // MESH_BED_LEVELING || AUTO_BED_LEVELING_UBL
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Buzzer/Speaker
|
* Buzzer/Speaker
|
||||||
*/
|
*/
|
||||||
@@ -811,6 +1049,18 @@
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* VIKI2, miniVIKI, and AZSMZ_12864 require DOGLCD_SCK and DOGLCD_MOSI to be defined.
|
||||||
|
*/
|
||||||
|
#if ENABLED(VIKI2) || ENABLED(miniVIKI) || ENABLED(AZSMZ_12864)
|
||||||
|
#ifndef DOGLCD_SCK
|
||||||
|
#define DOGLCD_SCK SCK_PIN
|
||||||
|
#endif
|
||||||
|
#ifndef DOGLCD_MOSI
|
||||||
|
#define DOGLCD_MOSI MOSI_PIN
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z_HOMING_HEIGHT / Z_CLEARANCE_BETWEEN_PROBES
|
* Z_HOMING_HEIGHT / Z_CLEARANCE_BETWEEN_PROBES
|
||||||
*/
|
*/
|
||||||
@@ -830,42 +1080,6 @@
|
|||||||
#define MANUAL_PROBE_HEIGHT Z_HOMING_HEIGHT
|
#define MANUAL_PROBE_HEIGHT Z_HOMING_HEIGHT
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
|
||||||
* Bed Probing rectangular bounds
|
|
||||||
* These can be further constrained in code for Delta and SCARA
|
|
||||||
*/
|
|
||||||
#if ENABLED(DELTA)
|
|
||||||
#ifndef DELTA_PROBEABLE_RADIUS
|
|
||||||
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
|
||||||
#endif
|
|
||||||
// Probing points may be verified at compile time within the radius
|
|
||||||
// using static_assert(HYPOT2(X2-X1,Y2-Y1)<=sq(DELTA_PRINTABLE_RADIUS),"bad probe point!")
|
|
||||||
// so that may be added to SanityCheck.h in the future.
|
|
||||||
#define MIN_PROBE_X (X_CENTER - (DELTA_PROBEABLE_RADIUS))
|
|
||||||
#define MIN_PROBE_Y (Y_CENTER - (DELTA_PROBEABLE_RADIUS))
|
|
||||||
#define MAX_PROBE_X (X_CENTER + DELTA_PROBEABLE_RADIUS)
|
|
||||||
#define MAX_PROBE_Y (Y_CENTER + DELTA_PROBEABLE_RADIUS)
|
|
||||||
#elif IS_SCARA
|
|
||||||
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
|
||||||
#define MIN_PROBE_X (X_CENTER - (SCARA_PRINTABLE_RADIUS))
|
|
||||||
#define MIN_PROBE_Y (Y_CENTER - (SCARA_PRINTABLE_RADIUS))
|
|
||||||
#define MAX_PROBE_X (X_CENTER + SCARA_PRINTABLE_RADIUS)
|
|
||||||
#define MAX_PROBE_Y (Y_CENTER + SCARA_PRINTABLE_RADIUS)
|
|
||||||
#else
|
|
||||||
// Boundaries for Cartesian probing based on set limits
|
|
||||||
#if ENABLED(BED_CENTER_AT_0_0)
|
|
||||||
#define MIN_PROBE_X (max(X_PROBE_OFFSET_FROM_EXTRUDER, 0) - (X_BED_SIZE) / 2)
|
|
||||||
#define MIN_PROBE_Y (max(Y_PROBE_OFFSET_FROM_EXTRUDER, 0) - (Y_BED_SIZE) / 2)
|
|
||||||
#define MAX_PROBE_X (min(X_BED_SIZE + X_PROBE_OFFSET_FROM_EXTRUDER, X_BED_SIZE) - (X_BED_SIZE) / 2)
|
|
||||||
#define MAX_PROBE_Y (min(Y_BED_SIZE + Y_PROBE_OFFSET_FROM_EXTRUDER, Y_BED_SIZE) - (Y_BED_SIZE) / 2)
|
|
||||||
#else
|
|
||||||
#define MIN_PROBE_X (max(X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER, 0))
|
|
||||||
#define MIN_PROBE_Y (max(Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER, 0))
|
|
||||||
#define MAX_PROBE_X (min(X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER, X_BED_SIZE))
|
|
||||||
#define MAX_PROBE_Y (min(Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER, Y_BED_SIZE))
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Stepper pulse duration, in cycles
|
// Stepper pulse duration, in cycles
|
||||||
#define STEP_PULSE_CYCLES ((MINIMUM_STEPPER_PULSE) * CYCLES_PER_MICROSECOND)
|
#define STEP_PULSE_CYCLES ((MINIMUM_STEPPER_PULSE) * CYCLES_PER_MICROSECOND)
|
||||||
|
|
||||||
@@ -876,7 +1090,7 @@
|
|||||||
// Updated G92 behavior shifts the workspace
|
// Updated G92 behavior shifts the workspace
|
||||||
#define HAS_POSITION_SHIFT DISABLED(NO_WORKSPACE_OFFSETS)
|
#define HAS_POSITION_SHIFT DISABLED(NO_WORKSPACE_OFFSETS)
|
||||||
// The home offset also shifts the coordinate space
|
// The home offset also shifts the coordinate space
|
||||||
#define HAS_HOME_OFFSET (DISABLED(NO_WORKSPACE_OFFSETS) || ENABLED(DELTA))
|
#define HAS_HOME_OFFSET (DISABLED(NO_WORKSPACE_OFFSETS) && DISABLED(DELTA))
|
||||||
// Either offset yields extra calculations on all moves
|
// Either offset yields extra calculations on all moves
|
||||||
#define HAS_WORKSPACE_OFFSET (HAS_POSITION_SHIFT || HAS_HOME_OFFSET)
|
#define HAS_WORKSPACE_OFFSET (HAS_POSITION_SHIFT || HAS_HOME_OFFSET)
|
||||||
// M206 doesn't apply to DELTA
|
// M206 doesn't apply to DELTA
|
||||||
@@ -887,31 +1101,11 @@
|
|||||||
#define LCD_TIMEOUT_TO_STATUS 15000
|
#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
|
||||||
* DELTA_SEGMENT_MIN_LENGTH for UBL_DELTA
|
|
||||||
*/
|
|
||||||
#if UBL_DELTA
|
|
||||||
#ifndef DELTA_SEGMENT_MIN_LENGTH
|
|
||||||
#if IS_SCARA
|
|
||||||
#define DELTA_SEGMENT_MIN_LENGTH 0.25 // SCARA minimum segment size is 0.25mm
|
|
||||||
#elif ENABLED(DELTA)
|
|
||||||
#define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DELTA_SEGMENTS_PER_SECOND)
|
|
||||||
#else // CARTESIAN
|
|
||||||
#define DELTA_SEGMENT_MIN_LENGTH 1.00 // mm (similar to G2/G3 arc segmentation)
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Shorthand
|
// Shorthand
|
||||||
#define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y))
|
#define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y))
|
||||||
|
|
||||||
// Add commands that need sub-codes to this list
|
// Add commands that need sub-codes to this list
|
||||||
#define USE_GCODE_SUBCODES ENABLED(G38_PROBE_TARGET)
|
#define USE_GCODE_SUBCODES ENABLED(G38_PROBE_TARGET) || ENABLED(CNC_COORDINATE_SYSTEMS)
|
||||||
|
|
||||||
// MESH_BED_LEVELING overrides PROBE_MANUALLY
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
|
||||||
#undef PROBE_MANUALLY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Parking Extruder
|
// Parking Extruder
|
||||||
#if ENABLED(PARKING_EXTRUDER)
|
#if ENABLED(PARKING_EXTRUDER)
|
||||||
@@ -923,4 +1117,34 @@
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Number of VFAT entries used. Each entry has 13 UTF-16 characters
|
||||||
|
#if ENABLED(SCROLL_LONG_FILENAMES)
|
||||||
|
#define MAX_VFAT_ENTRIES (5)
|
||||||
|
#else
|
||||||
|
#define MAX_VFAT_ENTRIES (2)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Set defaults for unspecified LED user colors
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#ifndef LED_USER_PRESET_RED
|
||||||
|
#define LED_USER_PRESET_RED 255
|
||||||
|
#endif
|
||||||
|
#ifndef LED_USER_PRESET_GREEN
|
||||||
|
#define LED_USER_PRESET_GREEN 255
|
||||||
|
#endif
|
||||||
|
#ifndef LED_USER_PRESET_BLUE
|
||||||
|
#define LED_USER_PRESET_BLUE 255
|
||||||
|
#endif
|
||||||
|
#ifndef LED_USER_PRESET_WHITE
|
||||||
|
#define LED_USER_PRESET_WHITE 0
|
||||||
|
#endif
|
||||||
|
#ifndef LED_USER_PRESET_BRIGHTNESS
|
||||||
|
#ifdef NEOPIXEL_BRIGHTNESS
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS NEOPIXEL_BRIGHTNESS
|
||||||
|
#else
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONDITIONALS_POST_H
|
#endif // CONDITIONALS_POST_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -428,12 +431,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -573,7 +577,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -686,14 +690,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -785,10 +791,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 200
|
#define Z_MAX_POS 200
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -808,7 +834,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -834,12 +860,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -866,6 +887,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -921,7 +960,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -932,8 +973,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
//#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -993,14 +1034,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (4*60)
|
#define HOMING_FEEDRATE_Z (4*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1032,7 +1130,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1177,11 +1275,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1418,11 +1516,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1525,12 +1625,19 @@
|
|||||||
//#define CR10_STOCKDISPLAY
|
//#define CR10_STOCKDISPLAY
|
||||||
|
|
||||||
//
|
//
|
||||||
// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
|
// MKS OLED 1.3" 128x64 FULL GRAPHICS CONTROLLER
|
||||||
// http://reprap.org/wiki/MKS_12864OLED
|
// http://reprap.org/wiki/MKS_12864OLED
|
||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
|
// If there is a pixel shift, try the other controller.
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1588,17 +1695,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1614,11 +1721,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1637,18 +1744,18 @@
|
|||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1661,40 +1768,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 2
|
#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 { 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.
|
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
File diff suppressed because it is too large
Load Diff
@@ -127,10 +127,7 @@
|
|||||||
invert = false,
|
invert = false,
|
||||||
ec = true;
|
ec = true;
|
||||||
|
|
||||||
float axisOffset = 0;
|
int32_t zeroOffset = 0,
|
||||||
|
|
||||||
int32_t axisOffsetTicks = 0,
|
|
||||||
zeroOffset = 0,
|
|
||||||
lastPosition = 0,
|
lastPosition = 0,
|
||||||
position;
|
position;
|
||||||
|
|
||||||
@@ -168,7 +165,7 @@
|
|||||||
}
|
}
|
||||||
|
|
||||||
FORCE_INLINE float get_position_mm() { return mm_from_count(get_position()); }
|
FORCE_INLINE float get_position_mm() { return mm_from_count(get_position()); }
|
||||||
FORCE_INLINE int32_t get_position() { return get_raw_count() - zeroOffset - axisOffsetTicks; }
|
FORCE_INLINE int32_t get_position() { return get_raw_count() - zeroOffset; }
|
||||||
|
|
||||||
int32_t get_axis_error_steps(const bool report);
|
int32_t get_axis_error_steps(const bool report);
|
||||||
float get_axis_error_mm(const bool report);
|
float get_axis_error_mm(const bool report);
|
||||||
@@ -219,16 +216,6 @@
|
|||||||
|
|
||||||
FORCE_INLINE int get_stepper_ticks() { return stepperTicks; }
|
FORCE_INLINE int get_stepper_ticks() { return stepperTicks; }
|
||||||
FORCE_INLINE void set_stepper_ticks(const int ticks) { stepperTicks = ticks; }
|
FORCE_INLINE void set_stepper_ticks(const int ticks) { stepperTicks = ticks; }
|
||||||
|
|
||||||
FORCE_INLINE float get_axis_offset() { return axisOffset; }
|
|
||||||
FORCE_INLINE void set_axis_offset(const float newOffset) {
|
|
||||||
axisOffset = newOffset;
|
|
||||||
axisOffsetTicks = int32_t(axisOffset * get_encoder_ticks_mm());
|
|
||||||
}
|
|
||||||
|
|
||||||
FORCE_INLINE void set_current_position(const float newPositionMm) {
|
|
||||||
set_axis_offset(get_position_mm() - newPositionMm + axisOffset);
|
|
||||||
}
|
|
||||||
};
|
};
|
||||||
|
|
||||||
class I2CPositionEncodersMgr {
|
class I2CPositionEncodersMgr {
|
||||||
|
|||||||
@@ -304,13 +304,8 @@ ifeq ($(HARDWARE_VARIANT), Teensy)
|
|||||||
SRC = wiring.c
|
SRC = wiring.c
|
||||||
VPATH += $(ARDUINO_INSTALL_DIR)/hardware/teensy/cores/teensy
|
VPATH += $(ARDUINO_INSTALL_DIR)/hardware/teensy/cores/teensy
|
||||||
endif
|
endif
|
||||||
CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \
|
CXXSRC = WMath.cpp WString.cpp Print.cpp SPI.cpp Tone.cpp
|
||||||
MarlinSerial.cpp Sd2Card.cpp SdBaseFile.cpp SdFatUtil.cpp \
|
CXXSRC += $(wildcard *.cpp)
|
||||||
SdFile.cpp SdVolume.cpp planner.cpp stepper.cpp \
|
|
||||||
temperature.cpp cardreader.cpp configuration_store.cpp \
|
|
||||||
watchdog.cpp SPI.cpp servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \
|
|
||||||
dac_mcp4728.cpp vector_3.cpp least_squares_fit.cpp endstops.cpp stopwatch.cpp utility.cpp \
|
|
||||||
printcounter.cpp nozzle.cpp serial.cpp gcode.cpp Max7219_Debug_LEDs.cpp
|
|
||||||
ifeq ($(NEOPIXEL), 1)
|
ifeq ($(NEOPIXEL), 1)
|
||||||
CXXSRC += Adafruit_NeoPixel.cpp
|
CXXSRC += Adafruit_NeoPixel.cpp
|
||||||
endif
|
endif
|
||||||
@@ -332,7 +327,7 @@ endif
|
|||||||
|
|
||||||
ifeq ($(RELOC_WORKAROUND), 1)
|
ifeq ($(RELOC_WORKAROUND), 1)
|
||||||
LD_PREFIX=-nodefaultlibs
|
LD_PREFIX=-nodefaultlibs
|
||||||
LD_SUFFIX=-lm -lgcc -lc -lgcc
|
LD_SUFFIX=-lm -lgcc -lc -lgcc -L$(ARDUINO_INSTALL_DIR)/hardware/tools/avr/avr/lib/avr6 -l$(MCU)
|
||||||
endif
|
endif
|
||||||
|
|
||||||
#Check for Arduino 1.0.0 or higher and use the correct source files for that version
|
#Check for Arduino 1.0.0 or higher and use the correct source files for that version
|
||||||
|
|||||||
137
Marlin/Marlin.h
137
Marlin/Marlin.h
@@ -210,17 +210,12 @@ inline void refresh_cmd_timeout() { previous_cmd_ms = millis(); }
|
|||||||
/**
|
/**
|
||||||
* Feedrate scaling and conversion
|
* Feedrate scaling and conversion
|
||||||
*/
|
*/
|
||||||
|
extern float feedrate_mm_s;
|
||||||
extern int16_t feedrate_percentage;
|
extern int16_t feedrate_percentage;
|
||||||
|
|
||||||
#define MMM_TO_MMS(MM_M) ((MM_M)/60.0)
|
|
||||||
#define MMS_TO_MMM(MM_S) ((MM_S)*60.0)
|
|
||||||
#define MMS_SCALED(MM_S) ((MM_S)*feedrate_percentage*0.01)
|
#define MMS_SCALED(MM_S) ((MM_S)*feedrate_percentage*0.01)
|
||||||
|
|
||||||
extern bool axis_relative_modes[];
|
extern bool axis_relative_modes[];
|
||||||
extern bool volumetric_enabled;
|
|
||||||
extern int16_t flow_percentage[EXTRUDERS]; // Extrusion factor for each extruder
|
|
||||||
extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder.
|
|
||||||
extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner
|
|
||||||
extern bool axis_known_position[XYZ];
|
extern bool axis_known_position[XYZ];
|
||||||
extern bool axis_homed[XYZ];
|
extern bool axis_homed[XYZ];
|
||||||
extern volatile bool wait_for_heatup;
|
extern volatile bool wait_for_heatup;
|
||||||
@@ -229,7 +224,7 @@ extern volatile bool wait_for_heatup;
|
|||||||
extern volatile bool wait_for_user;
|
extern volatile bool wait_for_user;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
extern float current_position[NUM_AXIS];
|
extern float current_position[XYZE], destination[XYZE];
|
||||||
|
|
||||||
// Workspace offsets
|
// Workspace offsets
|
||||||
#if HAS_WORKSPACE_OFFSET
|
#if HAS_WORKSPACE_OFFSET
|
||||||
@@ -252,14 +247,14 @@ extern float current_position[NUM_AXIS];
|
|||||||
#define WORKSPACE_OFFSET(AXIS) 0
|
#define WORKSPACE_OFFSET(AXIS) 0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define LOGICAL_POSITION(POS, AXIS) ((POS) + WORKSPACE_OFFSET(AXIS))
|
#define NATIVE_TO_LOGICAL(POS, AXIS) ((POS) + WORKSPACE_OFFSET(AXIS))
|
||||||
#define RAW_POSITION(POS, AXIS) ((POS) - WORKSPACE_OFFSET(AXIS))
|
#define LOGICAL_TO_NATIVE(POS, AXIS) ((POS) - WORKSPACE_OFFSET(AXIS))
|
||||||
|
|
||||||
#if HAS_POSITION_SHIFT || DISABLED(DELTA)
|
#if HAS_POSITION_SHIFT || DISABLED(DELTA)
|
||||||
#define LOGICAL_X_POSITION(POS) LOGICAL_POSITION(POS, X_AXIS)
|
#define LOGICAL_X_POSITION(POS) NATIVE_TO_LOGICAL(POS, X_AXIS)
|
||||||
#define LOGICAL_Y_POSITION(POS) LOGICAL_POSITION(POS, Y_AXIS)
|
#define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS)
|
||||||
#define RAW_X_POSITION(POS) RAW_POSITION(POS, X_AXIS)
|
#define RAW_X_POSITION(POS) LOGICAL_TO_NATIVE(POS, X_AXIS)
|
||||||
#define RAW_Y_POSITION(POS) RAW_POSITION(POS, Y_AXIS)
|
#define RAW_Y_POSITION(POS) LOGICAL_TO_NATIVE(POS, Y_AXIS)
|
||||||
#else
|
#else
|
||||||
#define LOGICAL_X_POSITION(POS) (POS)
|
#define LOGICAL_X_POSITION(POS) (POS)
|
||||||
#define LOGICAL_Y_POSITION(POS) (POS)
|
#define LOGICAL_Y_POSITION(POS) (POS)
|
||||||
@@ -267,9 +262,8 @@ extern float current_position[NUM_AXIS];
|
|||||||
#define RAW_Y_POSITION(POS) (POS)
|
#define RAW_Y_POSITION(POS) (POS)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define LOGICAL_Z_POSITION(POS) LOGICAL_POSITION(POS, Z_AXIS)
|
#define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS)
|
||||||
#define RAW_Z_POSITION(POS) RAW_POSITION(POS, Z_AXIS)
|
#define RAW_Z_POSITION(POS) LOGICAL_TO_NATIVE(POS, Z_AXIS)
|
||||||
#define RAW_CURRENT_POSITION(A) RAW_##A##_POSITION(current_position[A##_AXIS])
|
|
||||||
|
|
||||||
// Hotend Offsets
|
// Hotend Offsets
|
||||||
#if HOTENDS > 1
|
#if HOTENDS > 1
|
||||||
@@ -291,29 +285,81 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
|
|||||||
void update_software_endstops(const AxisEnum axis);
|
void update_software_endstops(const AxisEnum axis);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(CNC_COORDINATE_SYSTEMS)
|
||||||
|
#define MAX_COORDINATE_SYSTEMS 9
|
||||||
|
extern float coordinate_system[MAX_COORDINATE_SYSTEMS][XYZ];
|
||||||
|
bool select_coordinate_system(const int8_t _new);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void report_current_position();
|
||||||
|
|
||||||
#if IS_KINEMATIC
|
#if IS_KINEMATIC
|
||||||
extern float delta[ABC];
|
extern float delta[ABC];
|
||||||
void inverse_kinematics(const float logical[XYZ]);
|
void inverse_kinematics(const float raw[XYZ]);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(DELTA)
|
#if ENABLED(DELTA)
|
||||||
extern float endstop_adj[ABC],
|
extern float delta_height,
|
||||||
|
delta_endstop_adj[ABC],
|
||||||
delta_radius,
|
delta_radius,
|
||||||
|
delta_tower_angle_trim[ABC],
|
||||||
|
delta_tower[ABC][2],
|
||||||
delta_diagonal_rod,
|
delta_diagonal_rod,
|
||||||
delta_calibration_radius,
|
delta_calibration_radius,
|
||||||
|
delta_diagonal_rod_2_tower[ABC],
|
||||||
delta_segments_per_second,
|
delta_segments_per_second,
|
||||||
delta_tower_angle_trim[ABC],
|
|
||||||
delta_clip_start_height;
|
delta_clip_start_height;
|
||||||
void recalc_delta_settings(float radius, float diagonal_rod, float tower_angle_trim[ABC]);
|
|
||||||
|
void recalc_delta_settings();
|
||||||
|
float delta_safe_distance_from_top();
|
||||||
|
|
||||||
|
#if ENABLED(DELTA_FAST_SQRT)
|
||||||
|
float Q_rsqrt(const float number);
|
||||||
|
#define _SQRT(n) (1.0f / Q_rsqrt(n))
|
||||||
|
#else
|
||||||
|
#define _SQRT(n) SQRT(n)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Macro to obtain the Z position of an individual tower
|
||||||
|
#define DELTA_Z(T) raw[Z_AXIS] + _SQRT( \
|
||||||
|
delta_diagonal_rod_2_tower[T] - HYPOT2( \
|
||||||
|
delta_tower[T][X_AXIS] - raw[X_AXIS], \
|
||||||
|
delta_tower[T][Y_AXIS] - raw[Y_AXIS] \
|
||||||
|
) \
|
||||||
|
)
|
||||||
|
|
||||||
|
#define DELTA_RAW_IK() do { \
|
||||||
|
delta[A_AXIS] = DELTA_Z(A_AXIS); \
|
||||||
|
delta[B_AXIS] = DELTA_Z(B_AXIS); \
|
||||||
|
delta[C_AXIS] = DELTA_Z(C_AXIS); \
|
||||||
|
}while(0)
|
||||||
|
|
||||||
#elif IS_SCARA
|
#elif IS_SCARA
|
||||||
void forward_kinematics_SCARA(const float &a, const float &b);
|
void forward_kinematics_SCARA(const float &a, const float &b);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
extern bool g26_debug_flag;
|
||||||
|
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
constexpr bool g26_debug_flag = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
|
#define _GET_MESH_X(I) (bilinear_start[X_AXIS] + (I) * bilinear_grid_spacing[X_AXIS])
|
||||||
|
#define _GET_MESH_Y(J) (bilinear_start[Y_AXIS] + (J) * bilinear_grid_spacing[Y_AXIS])
|
||||||
|
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
#define _GET_MESH_X(I) ubl.mesh_index_to_xpos(I)
|
||||||
|
#define _GET_MESH_Y(J) ubl.mesh_index_to_ypos(J)
|
||||||
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
#define _GET_MESH_X(I) mbl.index_to_xpos[I]
|
||||||
|
#define _GET_MESH_Y(J) mbl.index_to_ypos[J]
|
||||||
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
extern int bilinear_grid_spacing[2], bilinear_start[2];
|
extern int bilinear_grid_spacing[2], bilinear_start[2];
|
||||||
extern float bilinear_grid_factor[2],
|
extern float bilinear_grid_factor[2],
|
||||||
z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
|
z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
|
||||||
float bilinear_z_offset(const float logical[XYZ]);
|
float bilinear_z_offset(const float raw[XYZ]);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
@@ -323,22 +369,26 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
|
|||||||
|
|
||||||
#if HAS_LEVELING
|
#if HAS_LEVELING
|
||||||
bool leveling_is_valid();
|
bool leveling_is_valid();
|
||||||
bool leveling_is_active();
|
|
||||||
void set_bed_leveling_enabled(const bool enable=true);
|
void set_bed_leveling_enabled(const bool enable=true);
|
||||||
void reset_bed_level();
|
void reset_bed_level();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
|
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
|
||||||
void set_z_fade_height(const float zfh);
|
void set_z_fade_height(const float zfh, const bool do_report=true);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
extern float x_endstop_adj;
|
||||||
|
#endif
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
extern float y_endstop_adj;
|
||||||
|
#endif
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
extern float z_endstop_adj;
|
extern float z_endstop_adj;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_BED_PROBE
|
#if HAS_BED_PROBE
|
||||||
extern float zprobe_zoffset;
|
extern float zprobe_zoffset;
|
||||||
void refresh_zprobe_zoffset(const bool no_babystep=false);
|
|
||||||
#define DEPLOY_PROBE() set_probe_deployed(true)
|
#define DEPLOY_PROBE() set_probe_deployed(true)
|
||||||
#define STOW_PROBE() set_probe_deployed(false)
|
#define STOW_PROBE() set_probe_deployed(false)
|
||||||
#else
|
#else
|
||||||
@@ -355,6 +405,10 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
|
|||||||
|
|
||||||
#if FAN_COUNT > 0
|
#if FAN_COUNT > 0
|
||||||
extern int16_t fanSpeeds[FAN_COUNT];
|
extern int16_t fanSpeeds[FAN_COUNT];
|
||||||
|
#if ENABLED(EXTRA_FAN_SPEED)
|
||||||
|
extern int16_t old_fanSpeeds[FAN_COUNT],
|
||||||
|
new_fanSpeeds[FAN_COUNT];
|
||||||
|
#endif
|
||||||
#if ENABLED(PROBING_FANS_OFF)
|
#if ENABLED(PROBING_FANS_OFF)
|
||||||
extern bool fans_paused;
|
extern bool fans_paused;
|
||||||
extern int16_t paused_fanSpeeds[FAN_COUNT];
|
extern int16_t paused_fanSpeeds[FAN_COUNT];
|
||||||
@@ -369,9 +423,9 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
|
|||||||
extern bool filament_sensor; // Flag that filament sensor readings should control extrusion
|
extern bool filament_sensor; // Flag that filament sensor readings should control extrusion
|
||||||
extern float filament_width_nominal, // Theoretical filament diameter i.e., 3.00 or 1.75
|
extern float filament_width_nominal, // Theoretical filament diameter i.e., 3.00 or 1.75
|
||||||
filament_width_meas; // Measured filament diameter
|
filament_width_meas; // Measured filament diameter
|
||||||
extern uint8_t meas_delay_cm, // Delay distance
|
extern uint8_t meas_delay_cm; // Delay distance
|
||||||
measurement_delay[]; // Ring buffer to delay measurement
|
extern int8_t measurement_delay[MAX_MEASUREMENT_DELAY + 1], // Ring buffer to delay measurement
|
||||||
extern int8_t filwidth_delay_index[2]; // Ring buffer indexes. Used by planner, temperature, and main code
|
filwidth_delay_index[2]; // Ring buffer indexes. Used by planner, temperature, and main code
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(ADVANCED_PAUSE_FEATURE)
|
#if ENABLED(ADVANCED_PAUSE_FEATURE)
|
||||||
@@ -404,15 +458,13 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
|
|||||||
// Handling multiple extruders pins
|
// Handling multiple extruders pins
|
||||||
extern uint8_t active_extruder;
|
extern uint8_t active_extruder;
|
||||||
|
|
||||||
#if HAS_TEMP_HOTEND || HAS_TEMP_BED
|
|
||||||
void print_heaterstates();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if ENABLED(MIXING_EXTRUDER)
|
#if ENABLED(MIXING_EXTRUDER)
|
||||||
extern float mixing_factor[MIXING_STEPPERS];
|
extern float mixing_factor[MIXING_STEPPERS];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void calculate_volumetric_multipliers();
|
inline void set_current_from_destination() { COPY(current_position, destination); }
|
||||||
|
inline void set_destination_from_current() { COPY(destination, current_position); }
|
||||||
|
void prepare_move_to_destination();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Blocking movement and shorthand functions
|
* Blocking movement and shorthand functions
|
||||||
@@ -430,6 +482,7 @@ void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s
|
|||||||
|| ENABLED(NOZZLE_CLEAN_FEATURE) \
|
|| ENABLED(NOZZLE_CLEAN_FEATURE) \
|
||||||
|| ENABLED(NOZZLE_PARK_FEATURE) \
|
|| ENABLED(NOZZLE_PARK_FEATURE) \
|
||||||
|| (ENABLED(ADVANCED_PAUSE_FEATURE) && ENABLED(HOME_BEFORE_FILAMENT_CHANGE)) \
|
|| (ENABLED(ADVANCED_PAUSE_FEATURE) && ENABLED(HOME_BEFORE_FILAMENT_CHANGE)) \
|
||||||
|
|| HAS_M206_COMMAND \
|
||||||
) || ENABLED(NO_MOTION_BEFORE_HOMING)
|
) || ENABLED(NO_MOTION_BEFORE_HOMING)
|
||||||
|
|
||||||
#if HAS_AXIS_UNHOMED_ERR
|
#if HAS_AXIS_UNHOMED_ERR
|
||||||
@@ -446,7 +499,7 @@ void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s
|
|||||||
extern const float L1, L2;
|
extern const float L1, L2;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
inline bool position_is_reachable_raw_xy(const float &rx, const float &ry) {
|
inline bool position_is_reachable(const float &rx, const float &ry) {
|
||||||
#if ENABLED(DELTA)
|
#if ENABLED(DELTA)
|
||||||
return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS);
|
return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS);
|
||||||
#elif IS_SCARA
|
#elif IS_SCARA
|
||||||
@@ -461,24 +514,24 @@ void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
inline bool position_is_reachable_by_probe_raw_xy(const float &rx, const float &ry) {
|
inline bool position_is_reachable_by_probe(const float &rx, const float &ry) {
|
||||||
|
|
||||||
// Both the nozzle and the probe must be able to reach the point.
|
// Both the nozzle and the probe must be able to reach the point.
|
||||||
// This won't work on SCARA since the probe offset rotates with the arm.
|
// This won't work on SCARA since the probe offset rotates with the arm.
|
||||||
|
|
||||||
return position_is_reachable_raw_xy(rx, ry)
|
return position_is_reachable(rx, ry)
|
||||||
&& position_is_reachable_raw_xy(rx - X_PROBE_OFFSET_FROM_EXTRUDER, ry - Y_PROBE_OFFSET_FROM_EXTRUDER);
|
&& position_is_reachable(rx - (X_PROBE_OFFSET_FROM_EXTRUDER), ry - (Y_PROBE_OFFSET_FROM_EXTRUDER));
|
||||||
}
|
}
|
||||||
|
|
||||||
#else // CARTESIAN
|
#else // CARTESIAN
|
||||||
|
|
||||||
inline bool position_is_reachable_raw_xy(const float &rx, const float &ry) {
|
inline bool position_is_reachable(const float &rx, const float &ry) {
|
||||||
// Add 0.001 margin to deal with float imprecision
|
// Add 0.001 margin to deal with float imprecision
|
||||||
return WITHIN(rx, X_MIN_POS - 0.001, X_MAX_POS + 0.001)
|
return WITHIN(rx, X_MIN_POS - 0.001, X_MAX_POS + 0.001)
|
||||||
&& WITHIN(ry, Y_MIN_POS - 0.001, Y_MAX_POS + 0.001);
|
&& WITHIN(ry, Y_MIN_POS - 0.001, Y_MAX_POS + 0.001);
|
||||||
}
|
}
|
||||||
|
|
||||||
inline bool position_is_reachable_by_probe_raw_xy(const float &rx, const float &ry) {
|
inline bool position_is_reachable_by_probe(const float &rx, const float &ry) {
|
||||||
// Add 0.001 margin to deal with float imprecision
|
// Add 0.001 margin to deal with float imprecision
|
||||||
return WITHIN(rx, MIN_PROBE_X - 0.001, MAX_PROBE_X + 0.001)
|
return WITHIN(rx, MIN_PROBE_X - 0.001, MAX_PROBE_X + 0.001)
|
||||||
&& WITHIN(ry, MIN_PROBE_Y - 0.001, MAX_PROBE_Y + 0.001);
|
&& WITHIN(ry, MIN_PROBE_Y - 0.001, MAX_PROBE_Y + 0.001);
|
||||||
@@ -486,12 +539,4 @@ void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s
|
|||||||
|
|
||||||
#endif // CARTESIAN
|
#endif // CARTESIAN
|
||||||
|
|
||||||
FORCE_INLINE bool position_is_reachable_by_probe_xy(const float &lx, const float &ly) {
|
|
||||||
return position_is_reachable_by_probe_raw_xy(RAW_X_POSITION(lx), RAW_Y_POSITION(ly));
|
|
||||||
}
|
|
||||||
|
|
||||||
FORCE_INLINE bool position_is_reachable_xy(const float &lx, const float &ly) {
|
|
||||||
return position_is_reachable_raw_xy(RAW_X_POSITION(lx), RAW_Y_POSITION(ly));
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // MARLIN_H
|
#endif // MARLIN_H
|
||||||
|
|||||||
@@ -29,6 +29,7 @@
|
|||||||
#include "Version.h"
|
#include "Version.h"
|
||||||
#include "Configuration.h"
|
#include "Configuration.h"
|
||||||
#include "Conditionals_LCD.h"
|
#include "Conditionals_LCD.h"
|
||||||
|
#include "tmc_macros.h"
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "pins.h"
|
#include "pins.h"
|
||||||
#ifndef USBCON
|
#ifndef USBCON
|
||||||
|
|||||||
@@ -20,8 +20,8 @@
|
|||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef __SPI_H__
|
#ifndef __MARLIN_SPI_H__
|
||||||
#define __SPI_H__
|
#define __MARLIN_SPI_H__
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include "softspi.h"
|
#include "softspi.h"
|
||||||
@@ -54,4 +54,4 @@ class SPI<MISO_PIN, MOSI_PIN, SCK_PIN> {
|
|||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // __SPI_H__
|
#endif // __MARLIN_SPI_H__
|
||||||
@@ -75,28 +75,18 @@
|
|||||||
#define BIN 2
|
#define BIN 2
|
||||||
#define BYTE 0
|
#define BYTE 0
|
||||||
|
|
||||||
#ifndef USBCON
|
// Define constants and variables for buffering serial data.
|
||||||
// Define constants and variables for buffering incoming serial data. We're
|
// Use only 0 or powers of 2 greater than 1
|
||||||
// using a ring buffer (I think), in which rx_buffer_head is the index of the
|
// : [0, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048, ...]
|
||||||
// location to which to write the next incoming character and rx_buffer_tail
|
#ifndef RX_BUFFER_SIZE
|
||||||
// is the index of the location from which to read.
|
|
||||||
// 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
|
#define RX_BUFFER_SIZE 128
|
||||||
#endif
|
#endif
|
||||||
#ifndef TX_BUFFER_SIZE
|
// 256 is the max TX buffer limit due to uint8_t head and tail.
|
||||||
|
#ifndef TX_BUFFER_SIZE
|
||||||
#define TX_BUFFER_SIZE 32
|
#define TX_BUFFER_SIZE 32
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(SERIAL_XON_XOFF) && RX_BUFFER_SIZE < 1024
|
#ifndef USBCON
|
||||||
#error "XON/XOFF requires RX_BUFFER_SIZE >= 1024 for reliable transfers without drops."
|
|
||||||
#endif
|
|
||||||
#if !IS_POWER_OF_2(RX_BUFFER_SIZE) || RX_BUFFER_SIZE < 2
|
|
||||||
#error "RX_BUFFER_SIZE must be a power of 2 greater than 1."
|
|
||||||
#endif
|
|
||||||
#if TX_BUFFER_SIZE && (TX_BUFFER_SIZE < 2 || TX_BUFFER_SIZE > 256 || !IS_POWER_OF_2(TX_BUFFER_SIZE))
|
|
||||||
#error "TX_BUFFER_SIZE must be 0 or a power of 2 greater than 1."
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if RX_BUFFER_SIZE > 256
|
#if RX_BUFFER_SIZE > 256
|
||||||
typedef uint16_t ring_buffer_pos_t;
|
typedef uint16_t ring_buffer_pos_t;
|
||||||
@@ -143,10 +133,10 @@
|
|||||||
static void printFloat(double, uint8_t);
|
static void printFloat(double, uint8_t);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
static FORCE_INLINE void write(const char* str) { while (*str) write(*str++); }
|
FORCE_INLINE static void write(const char* str) { while (*str) write(*str++); }
|
||||||
static FORCE_INLINE void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
|
FORCE_INLINE static void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
|
||||||
static FORCE_INLINE void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
|
FORCE_INLINE static void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
|
||||||
static FORCE_INLINE void print(const char* str) { write(str); }
|
FORCE_INLINE static void print(const char* str) { write(str); }
|
||||||
|
|
||||||
static void print(char, int = BYTE);
|
static void print(char, int = BYTE);
|
||||||
static void print(unsigned char, int = BYTE);
|
static void print(unsigned char, int = BYTE);
|
||||||
|
|||||||
File diff suppressed because it is too large
Load Diff
@@ -39,12 +39,14 @@
|
|||||||
* void Max7219_init();
|
* void Max7219_init();
|
||||||
* void Max7219_PutByte(uint8_t data);
|
* void Max7219_PutByte(uint8_t data);
|
||||||
* void Max7219(uint8_t reg, uint8_t data);
|
* void Max7219(uint8_t reg, uint8_t data);
|
||||||
* void Max7219_LED_On(uint8_t row, uint8_t col);
|
* void Max7219_LED_On(uint8_t col, uint8_t row);
|
||||||
* void Max7219_LED_Off(uint8_t row, uint8_t col);
|
* void Max7219_LED_Off(uint8_t col, uint8_t row);
|
||||||
* void Max7219_LED_Toggle(uint8_t row, uint8_t col);
|
* void Max7219_LED_Toggle(uint8_t col, uint8_t row);
|
||||||
* void Max7219_Clear_Row(uint8_t row);
|
* void Max7219_Clear_Row(uint8_t row);
|
||||||
* void Max7219_Clear_Column(uint8_t col);
|
* void Max7219_Clear_Column(uint8_t col);
|
||||||
* void Max7219_Set_Row(uint8_t row, uint8_t val);
|
* void Max7219_Set_Row(uint8_t row, uint8_t val);
|
||||||
|
* void Max7219_Set_2_Rows(uint8_t row, uint16_t val);
|
||||||
|
* void Max7219_Set_4_Rows(uint8_t row, uint32_t val);
|
||||||
* void Max7219_Set_Column(uint8_t col, uint8_t val);
|
* void Max7219_Set_Column(uint8_t col, uint8_t val);
|
||||||
* void Max7219_idle_tasks();
|
* void Max7219_idle_tasks();
|
||||||
*/
|
*/
|
||||||
@@ -53,87 +55,173 @@
|
|||||||
|
|
||||||
#if ENABLED(MAX7219_DEBUG)
|
#if ENABLED(MAX7219_DEBUG)
|
||||||
|
|
||||||
#include "Marlin.h"
|
#include "Max7219_Debug_LEDs.h"
|
||||||
#include "planner.h"
|
|
||||||
#include "stepper.h"
|
|
||||||
#include "Max7219_Debug_LEDs.h"
|
|
||||||
|
|
||||||
static uint8_t LEDs[8] = { 0 };
|
#include "planner.h"
|
||||||
|
#include "stepper.h"
|
||||||
|
#include "Marlin.h"
|
||||||
|
|
||||||
void Max7219_PutByte(uint8_t data) {
|
static uint8_t LEDs[8] = { 0 };
|
||||||
|
|
||||||
|
#ifdef CPU_32_BIT
|
||||||
|
#define MS_DELAY() delayMicroseconds(5) // 32-bit processors need a delay to stabilize the signal
|
||||||
|
#else
|
||||||
|
#define MS_DELAY() NOOP
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void Max7219_PutByte(uint8_t data) {
|
||||||
|
CRITICAL_SECTION_START
|
||||||
for (uint8_t i = 8; i--;) {
|
for (uint8_t i = 8; i--;) {
|
||||||
|
MS_DELAY();
|
||||||
WRITE(MAX7219_CLK_PIN, LOW); // tick
|
WRITE(MAX7219_CLK_PIN, LOW); // tick
|
||||||
|
MS_DELAY();
|
||||||
WRITE(MAX7219_DIN_PIN, (data & 0x80) ? HIGH : LOW); // send 1 or 0 based on data bit
|
WRITE(MAX7219_DIN_PIN, (data & 0x80) ? HIGH : LOW); // send 1 or 0 based on data bit
|
||||||
|
MS_DELAY();
|
||||||
WRITE(MAX7219_CLK_PIN, HIGH); // tock
|
WRITE(MAX7219_CLK_PIN, HIGH); // tock
|
||||||
|
MS_DELAY();
|
||||||
data <<= 1;
|
data <<= 1;
|
||||||
}
|
}
|
||||||
}
|
CRITICAL_SECTION_END
|
||||||
|
}
|
||||||
|
|
||||||
void Max7219(const uint8_t reg, const uint8_t data) {
|
void Max7219(const uint8_t reg, const uint8_t data) {
|
||||||
|
MS_DELAY();
|
||||||
|
CRITICAL_SECTION_START
|
||||||
WRITE(MAX7219_LOAD_PIN, LOW); // begin
|
WRITE(MAX7219_LOAD_PIN, LOW); // begin
|
||||||
|
MS_DELAY();
|
||||||
Max7219_PutByte(reg); // specify register
|
Max7219_PutByte(reg); // specify register
|
||||||
|
MS_DELAY();
|
||||||
Max7219_PutByte(data); // put data
|
Max7219_PutByte(data); // put data
|
||||||
|
MS_DELAY();
|
||||||
WRITE(MAX7219_LOAD_PIN, LOW); // and tell the chip to load the data
|
WRITE(MAX7219_LOAD_PIN, LOW); // and tell the chip to load the data
|
||||||
|
MS_DELAY();
|
||||||
WRITE(MAX7219_LOAD_PIN, HIGH);
|
WRITE(MAX7219_LOAD_PIN, HIGH);
|
||||||
}
|
CRITICAL_SECTION_END
|
||||||
|
MS_DELAY();
|
||||||
|
}
|
||||||
|
|
||||||
void Max7219_LED_Set(const uint8_t row, const uint8_t col, const bool on) {
|
void Max7219_LED_Set(const uint8_t row, const uint8_t col, const bool on) {
|
||||||
if (row > 7 || col > 7) return;
|
if (row > 7 || col > 7) {
|
||||||
|
SERIAL_ECHOPAIR("??? Max7219_LED_Set(", (int)row);
|
||||||
|
SERIAL_ECHOPAIR(",", (int)col);
|
||||||
|
SERIAL_ECHOLNPGM(")");
|
||||||
|
return;
|
||||||
|
}
|
||||||
if (TEST(LEDs[row], col) == on) return; // if LED is already on/off, leave alone
|
if (TEST(LEDs[row], col) == on) return; // if LED is already on/off, leave alone
|
||||||
if (on) SBI(LEDs[row], col); else CBI(LEDs[row], col);
|
if (on) SBI(LEDs[row], col); else CBI(LEDs[row], col);
|
||||||
Max7219(8 - row, LEDs[row]);
|
Max7219(8 - row, LEDs[row]);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Max7219_LED_On(const uint8_t row, const uint8_t col) {
|
void Max7219_LED_On(const uint8_t col, const uint8_t row) {
|
||||||
Max7219_LED_Set(row, col, true);
|
if (row > 7 || col > 7) {
|
||||||
|
SERIAL_ECHOPAIR("??? Max7219_LED_On(", (int)col);
|
||||||
|
SERIAL_ECHOPAIR(",", (int)row);
|
||||||
|
SERIAL_ECHOLNPGM(")");
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
|
Max7219_LED_Set(col, row, true);
|
||||||
|
}
|
||||||
|
|
||||||
void Max7219_LED_Off(const uint8_t row, const uint8_t col) {
|
void Max7219_LED_Off(const uint8_t col, const uint8_t row) {
|
||||||
Max7219_LED_Set(row, col, false);
|
if (row > 7 || col > 7) {
|
||||||
|
SERIAL_ECHOPAIR("??? Max7219_LED_Off(", (int)row);
|
||||||
|
SERIAL_ECHOPAIR(",", (int)col);
|
||||||
|
SERIAL_ECHOLNPGM(")");
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
|
Max7219_LED_Set(col, row, false);
|
||||||
|
}
|
||||||
|
|
||||||
void Max7219_LED_Toggle(const uint8_t row, const uint8_t col) {
|
void Max7219_LED_Toggle(const uint8_t col, const uint8_t row) {
|
||||||
if (row > 7 || col > 7) return;
|
if (row > 7 || col > 7) {
|
||||||
|
SERIAL_ECHOPAIR("??? Max7219_LED_Toggle(", (int)row);
|
||||||
|
SERIAL_ECHOPAIR(",", (int)col);
|
||||||
|
SERIAL_ECHOLNPGM(")");
|
||||||
|
return;
|
||||||
|
}
|
||||||
if (TEST(LEDs[row], col))
|
if (TEST(LEDs[row], col))
|
||||||
Max7219_LED_Off(row, col);
|
Max7219_LED_Off(col, row);
|
||||||
else
|
else
|
||||||
Max7219_LED_On(row, col);
|
Max7219_LED_On(col, row);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Max7219_Clear_Column(const uint8_t col) {
|
void Max7219_Clear_Column(const uint8_t col) {
|
||||||
if (col > 7) return;
|
if (col > 7) {
|
||||||
|
SERIAL_ECHOPAIR("??? Max7219_Clear_Column(", (int)col);
|
||||||
|
SERIAL_ECHOLNPGM(")");
|
||||||
|
return;
|
||||||
|
}
|
||||||
LEDs[col] = 0;
|
LEDs[col] = 0;
|
||||||
Max7219(8 - col, LEDs[col]);
|
Max7219(8 - col, LEDs[col]);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Max7219_Clear_Row(const uint8_t row) {
|
void Max7219_Clear_Row(const uint8_t row) {
|
||||||
if (row > 7) return;
|
if (row > 7) {
|
||||||
|
SERIAL_ECHOPAIR("??? Max7219_Clear_Row(", (int)row);
|
||||||
|
SERIAL_ECHOLNPGM(")");
|
||||||
|
return;
|
||||||
|
}
|
||||||
for (uint8_t c = 0; c <= 7; c++)
|
for (uint8_t c = 0; c <= 7; c++)
|
||||||
Max7219_LED_Off(c, row);
|
Max7219_LED_Off(c, row);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Max7219_Set_Row(const uint8_t row, const uint8_t val) {
|
void Max7219_Set_Row(const uint8_t row, const uint8_t val) {
|
||||||
if (row > 7) return;
|
if (row > 7) {
|
||||||
|
SERIAL_ECHOPAIR("??? Max7219_Set_Row(", (int)row);
|
||||||
|
SERIAL_ECHOPAIR(",", (int)val);
|
||||||
|
SERIAL_ECHOLNPGM(")");
|
||||||
|
return;
|
||||||
|
}
|
||||||
for (uint8_t b = 0; b <= 7; b++)
|
for (uint8_t b = 0; b <= 7; b++)
|
||||||
if (TEST(val, b))
|
if (TEST(val, b))
|
||||||
Max7219_LED_On(7 - b, row);
|
Max7219_LED_On(7 - b, row);
|
||||||
else
|
else
|
||||||
Max7219_LED_Off(7 - b, row);
|
Max7219_LED_Off(7 - b, row);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Max7219_Set_Column(const uint8_t col, const uint8_t val) {
|
void Max7219_Set_2_Rows(const uint8_t row, const uint16_t val) {
|
||||||
if (col > 7) return;
|
if (row > 6) {
|
||||||
|
SERIAL_ECHOPAIR("??? Max7219_Set_2_Rows(", (int)row);
|
||||||
|
SERIAL_ECHOPAIR(",", (int)val);
|
||||||
|
SERIAL_ECHOLNPGM(")");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
Max7219_Set_Row(row + 1, (val >> 8) & 0xFF);
|
||||||
|
Max7219_Set_Row(row + 0, (val ) & 0xFF);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Max7219_Set_4_Rows(const uint8_t row, const uint32_t val) {
|
||||||
|
if (row > 4) {
|
||||||
|
SERIAL_ECHOPAIR("??? Max7219_Set_4_Rows(", (int)row);
|
||||||
|
SERIAL_ECHOPAIR(",", (long)val);
|
||||||
|
SERIAL_ECHOLNPGM(")");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
Max7219_Set_Row(row + 3, (val >> 24) & 0xFF);
|
||||||
|
Max7219_Set_Row(row + 2, (val >> 16) & 0xFF);
|
||||||
|
Max7219_Set_Row(row + 1, (val >> 8) & 0xFF);
|
||||||
|
Max7219_Set_Row(row + 0, (val ) & 0xFF);
|
||||||
|
}
|
||||||
|
|
||||||
|
void Max7219_Set_Column(const uint8_t col, const uint8_t val) {
|
||||||
|
if (col > 7) {
|
||||||
|
SERIAL_ECHOPAIR("??? Max7219_Column(", (int)col);
|
||||||
|
SERIAL_ECHOPAIR(",", (int)val);
|
||||||
|
SERIAL_ECHOLNPGM(")");
|
||||||
|
return;
|
||||||
|
}
|
||||||
LEDs[col] = val;
|
LEDs[col] = val;
|
||||||
Max7219(8 - col, LEDs[col]);
|
Max7219(8 - col, LEDs[col]);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Max7219_init() {
|
void Max7219_init() {
|
||||||
uint8_t i, x, y;
|
uint8_t i, x, y;
|
||||||
|
|
||||||
SET_OUTPUT(MAX7219_DIN_PIN);
|
SET_OUTPUT(MAX7219_DIN_PIN);
|
||||||
SET_OUTPUT(MAX7219_CLK_PIN);
|
SET_OUTPUT(MAX7219_CLK_PIN);
|
||||||
|
|
||||||
OUT_WRITE(MAX7219_LOAD_PIN, HIGH);
|
OUT_WRITE(MAX7219_LOAD_PIN, HIGH);
|
||||||
|
delay(1);
|
||||||
|
|
||||||
//initiation of the max 7219
|
//initiation of the max 7219
|
||||||
Max7219(max7219_reg_scanLimit, 0x07);
|
Max7219(max7219_reg_scanLimit, 0x07);
|
||||||
@@ -172,47 +260,72 @@
|
|||||||
Max7219_LED_Off(x, y);
|
Max7219_LED_Off(x, y);
|
||||||
delay(2);
|
delay(2);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* These are sample debug features to demonstrate the usage of the 8x8 LED Matrix for debug purposes.
|
* These are sample debug features to demonstrate the usage of the 8x8 LED Matrix for debug purposes.
|
||||||
* There is very little CPU burden added to the system by displaying information within the idle()
|
* There is very little CPU burden added to the system by displaying information within the idle()
|
||||||
* task.
|
* task.
|
||||||
*
|
*
|
||||||
* But with that said, if your debugging can be facilitated by making calls into the library from
|
* But with that said, if your debugging can be facilitated by making calls into the library from
|
||||||
* other places in the code, feel free to do it. The CPU burden for a few calls to toggle an LED
|
* other places in the code, feel free to do it. The CPU burden for a few calls to toggle an LED
|
||||||
* or clear a row is not very significant.
|
* or clear a row is not very significant.
|
||||||
*/
|
*/
|
||||||
void Max7219_idle_tasks() {
|
void Max7219_idle_tasks() {
|
||||||
|
#if MAX7219_DEBUG_STEPPER_HEAD || MAX7219_DEBUG_STEPPER_TAIL || MAX7219_DEBUG_STEPPER_QUEUE
|
||||||
|
CRITICAL_SECTION_START
|
||||||
|
#if MAX7219_DEBUG_STEPPER_HEAD || MAX7219_DEBUG_STEPPER_QUEUE
|
||||||
|
const uint8_t head = planner.block_buffer_head;
|
||||||
|
#endif
|
||||||
|
#if MAX7219_DEBUG_STEPPER_TAIL || MAX7219_DEBUG_STEPPER_QUEUE
|
||||||
|
const uint8_t tail = planner.block_buffer_tail;
|
||||||
|
#endif
|
||||||
|
CRITICAL_SECTION_END
|
||||||
|
#endif
|
||||||
|
|
||||||
#if ENABLED(MAX7219_DEBUG_PRINTER_ALIVE)
|
#if ENABLED(MAX7219_DEBUG_PRINTER_ALIVE)
|
||||||
static int debug_cnt = 0;
|
static millis_t next_blink = 0;
|
||||||
if (debug_cnt++ > 100) {
|
if (ELAPSED(millis(), next_blink)) {
|
||||||
Max7219_LED_Toggle(7, 7);
|
Max7219_LED_Toggle(7, 7);
|
||||||
debug_cnt = 0;
|
next_blink = millis() + 750;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef MAX7219_DEBUG_STEPPER_HEAD
|
#ifdef MAX7219_DEBUG_STEPPER_HEAD
|
||||||
Max7219_Clear_Row(MAX7219_DEBUG_STEPPER_HEAD);
|
static int16_t last_head_cnt = 0;
|
||||||
Max7219_Clear_Row(MAX7219_DEBUG_STEPPER_HEAD + 1);
|
if (last_head_cnt != head) {
|
||||||
if ( planner.block_buffer_head < 8)
|
if (last_head_cnt < 8)
|
||||||
Max7219_LED_On( planner.block_buffer_head, MAX7219_DEBUG_STEPPER_HEAD);
|
Max7219_LED_Off(last_head_cnt, MAX7219_DEBUG_STEPPER_HEAD);
|
||||||
else
|
else
|
||||||
Max7219_LED_On( planner.block_buffer_head-8, MAX7219_DEBUG_STEPPER_HEAD+1);
|
Max7219_LED_Off(last_head_cnt - 8, MAX7219_DEBUG_STEPPER_HEAD + 1);
|
||||||
|
|
||||||
|
last_head_cnt = head;
|
||||||
|
if (head < 8)
|
||||||
|
Max7219_LED_On(head, MAX7219_DEBUG_STEPPER_HEAD);
|
||||||
|
else
|
||||||
|
Max7219_LED_On(head - 8, MAX7219_DEBUG_STEPPER_HEAD + 1);
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef MAX7219_DEBUG_STEPPER_TAIL
|
#ifdef MAX7219_DEBUG_STEPPER_TAIL
|
||||||
Max7219_Clear_Row(MAX7219_DEBUG_STEPPER_TAIL);
|
static int16_t last_tail_cnt = 0;
|
||||||
Max7219_Clear_Row(MAX7219_DEBUG_STEPPER_TAIL + 1);
|
if (last_tail_cnt != tail) {
|
||||||
if ( planner.block_buffer_tail < 8)
|
if (last_tail_cnt < 8)
|
||||||
Max7219_LED_On( planner.block_buffer_tail, MAX7219_DEBUG_STEPPER_TAIL );
|
Max7219_LED_Off(last_tail_cnt, MAX7219_DEBUG_STEPPER_TAIL);
|
||||||
else
|
else
|
||||||
Max7219_LED_On( planner.block_buffer_tail-8, MAX7219_DEBUG_STEPPER_TAIL+1 );
|
Max7219_LED_Off(last_tail_cnt - 8, MAX7219_DEBUG_STEPPER_TAIL + 1);
|
||||||
|
|
||||||
|
last_tail_cnt = tail;
|
||||||
|
if (tail < 8)
|
||||||
|
Max7219_LED_On(tail, MAX7219_DEBUG_STEPPER_TAIL);
|
||||||
|
else
|
||||||
|
Max7219_LED_On(tail - 8, MAX7219_DEBUG_STEPPER_TAIL + 1);
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef MAX7219_DEBUG_STEPPER_QUEUE
|
#ifdef MAX7219_DEBUG_STEPPER_QUEUE
|
||||||
static int16_t last_depth = 0;
|
static int16_t last_depth = 0;
|
||||||
int16_t current_depth = planner.block_buffer_head - planner.block_buffer_tail;
|
int16_t current_depth = head - tail;
|
||||||
if (current_depth != last_depth) { // usually, no update will be needed.
|
if (current_depth != last_depth) { // usually, no update will be needed.
|
||||||
if (current_depth < 0) current_depth += BLOCK_BUFFER_SIZE;
|
if (current_depth < 0) current_depth += BLOCK_BUFFER_SIZE;
|
||||||
NOMORE(current_depth, BLOCK_BUFFER_SIZE);
|
NOMORE(current_depth, BLOCK_BUFFER_SIZE);
|
||||||
@@ -223,14 +336,14 @@
|
|||||||
en = max(current_depth, last_depth);
|
en = max(current_depth, last_depth);
|
||||||
if (current_depth < last_depth)
|
if (current_depth < last_depth)
|
||||||
for (uint8_t i = st; i <= en; i++) // clear the highest order LEDs
|
for (uint8_t i = st; i <= en; i++) // clear the highest order LEDs
|
||||||
Max7219_LED_Off(i >> 1, MAX7219_DEBUG_STEPPER_QUEUE + (i & 1));
|
Max7219_LED_Off(i / 2, MAX7219_DEBUG_STEPPER_QUEUE + (i & 1));
|
||||||
else
|
else
|
||||||
for (uint8_t i = st; i <= en; i++) // set the highest order LEDs
|
for (uint8_t i = st; i <= en; i++) // set the LEDs to current depth
|
||||||
Max7219_LED_On(i >> 1, MAX7219_DEBUG_STEPPER_QUEUE + (i & 1));
|
Max7219_LED_On(i / 2, MAX7219_DEBUG_STEPPER_QUEUE + (i & 1));
|
||||||
|
|
||||||
last_depth = current_depth;
|
last_depth = current_depth;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // MAX7219_DEBUG
|
#endif // MAX7219_DEBUG
|
||||||
|
|||||||
@@ -40,12 +40,14 @@
|
|||||||
* void Max7219_PutByte(uint8_t data);
|
* void Max7219_PutByte(uint8_t data);
|
||||||
* void Max7219(uint8_t reg, uint8_t data);
|
* void Max7219(uint8_t reg, uint8_t data);
|
||||||
* void Max7219_LED_Set(uint8_t row, uint8_t col, bool on);
|
* void Max7219_LED_Set(uint8_t row, uint8_t col, bool on);
|
||||||
* void Max7219_LED_On(uint8_t row, uint8_t col);
|
* void Max7219_LED_On(uint8_t col, uint8_t row);
|
||||||
* void Max7219_LED_Off(uint8_t row, uint8_t col);
|
* void Max7219_LED_Off(uint8_t col, uint8_t row);
|
||||||
* void Max7219_LED_Toggle(uint8_t row, uint8_t col);
|
* void Max7219_LED_Toggle(uint8_t row, uint8_t col);
|
||||||
* void Max7219_Clear_Row(uint8_t row);
|
* void Max7219_Clear_Row(uint8_t row);
|
||||||
* void Max7219_Clear_Column(uint8_t col);
|
* void Max7219_Clear_Column(uint8_t col);
|
||||||
* void Max7219_Set_Row(uint8_t row, uint8_t val);
|
* void Max7219_Set_Row(uint8_t row, uint8_t val);
|
||||||
|
* void Max7219_Set_2_Rows(uint8_t row, uint16_t val);
|
||||||
|
* void Max7219_Set_4_Rows(uint8_t row, uint32_t val);
|
||||||
* void Max7219_Set_Column(uint8_t col, uint8_t val);
|
* void Max7219_Set_Column(uint8_t col, uint8_t val);
|
||||||
* void Max7219_idle_tasks();
|
* void Max7219_idle_tasks();
|
||||||
*/
|
*/
|
||||||
@@ -53,36 +55,36 @@
|
|||||||
#ifndef __MAX7219_DEBUG_LEDS_H__
|
#ifndef __MAX7219_DEBUG_LEDS_H__
|
||||||
#define __MAX7219_DEBUG_LEDS_H__
|
#define __MAX7219_DEBUG_LEDS_H__
|
||||||
|
|
||||||
//
|
//
|
||||||
// define max7219 registers
|
// define max7219 registers
|
||||||
//
|
//
|
||||||
#define max7219_reg_noop 0x00
|
#define max7219_reg_noop 0x00
|
||||||
#define max7219_reg_digit0 0x01
|
#define max7219_reg_digit0 0x01
|
||||||
#define max7219_reg_digit1 0x02
|
#define max7219_reg_digit1 0x02
|
||||||
#define max7219_reg_digit2 0x03
|
#define max7219_reg_digit2 0x03
|
||||||
#define max7219_reg_digit3 0x04
|
#define max7219_reg_digit3 0x04
|
||||||
#define max7219_reg_digit4 0x05
|
#define max7219_reg_digit4 0x05
|
||||||
#define max7219_reg_digit5 0x06
|
#define max7219_reg_digit5 0x06
|
||||||
#define max7219_reg_digit6 0x07
|
#define max7219_reg_digit6 0x07
|
||||||
#define max7219_reg_digit7 0x08
|
#define max7219_reg_digit7 0x08
|
||||||
|
|
||||||
#define max7219_reg_intensity 0x0A
|
#define max7219_reg_intensity 0x0A
|
||||||
#define max7219_reg_displayTest 0x0F
|
#define max7219_reg_displayTest 0x0F
|
||||||
#define max7219_reg_decodeMode 0x09
|
#define max7219_reg_decodeMode 0x09
|
||||||
#define max7219_reg_scanLimit 0x0B
|
#define max7219_reg_scanLimit 0x0B
|
||||||
#define max7219_reg_shutdown 0x0C
|
#define max7219_reg_shutdown 0x0C
|
||||||
|
|
||||||
void Max7219_init();
|
void Max7219_init();
|
||||||
void Max7219_PutByte(uint8_t data);
|
void Max7219_PutByte(uint8_t data);
|
||||||
void Max7219(const uint8_t reg, const uint8_t data);
|
void Max7219(const uint8_t reg, const uint8_t data);
|
||||||
void Max7219_LED_Set(const uint8_t row, const uint8_t col, const bool on);
|
void Max7219_LED_Set(const uint8_t row, const uint8_t col, const bool on);
|
||||||
void Max7219_LED_On(const uint8_t row, const uint8_t col);
|
void Max7219_LED_On(const uint8_t row, const uint8_t col);
|
||||||
void Max7219_LED_Off(const uint8_t row, const uint8_t col);
|
void Max7219_LED_Off(const uint8_t row, const uint8_t col);
|
||||||
void Max7219_LED_Toggle(const uint8_t row, const uint8_t col);
|
void Max7219_LED_Toggle(const uint8_t row, const uint8_t col);
|
||||||
void Max7219_Clear_Row(const uint8_t row);
|
void Max7219_Clear_Row(const uint8_t row);
|
||||||
void Max7219_Clear_Column(const uint8_t col);
|
void Max7219_Clear_Column(const uint8_t col);
|
||||||
void Max7219_Set_Row(const uint8_t row, const uint8_t val);
|
void Max7219_Set_Row(const uint8_t row, const uint8_t val);
|
||||||
void Max7219_Set_Column(const uint8_t col, const uint8_t val);
|
void Max7219_Set_Column(const uint8_t col, const uint8_t val);
|
||||||
void Max7219_idle_tasks();
|
void Max7219_idle_tasks();
|
||||||
|
|
||||||
#endif // __MAX7219_DEBUG_LEDS_H__
|
#endif // __MAX7219_DEBUG_LEDS_H__
|
||||||
|
|||||||
@@ -26,6 +26,9 @@
|
|||||||
* Test configuration values for errors at compile-time.
|
* Test configuration values for errors at compile-time.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#ifndef _SANITYCHECK_H_
|
||||||
|
#define _SANITYCHECK_H_
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Require gcc 4.7 or newer (first included with Arduino 1.6.8) for C++11 features.
|
* Require gcc 4.7 or newer (first included with Arduino 1.6.8) for C++11 features.
|
||||||
*/
|
*/
|
||||||
@@ -78,8 +81,6 @@
|
|||||||
#error "FILAMENT_SENSOR is deprecated. Use FILAMENT_WIDTH_SENSOR instead."
|
#error "FILAMENT_SENSOR is deprecated. Use FILAMENT_WIDTH_SENSOR instead."
|
||||||
#elif defined(DISABLE_MAX_ENDSTOPS) || defined(DISABLE_MIN_ENDSTOPS)
|
#elif defined(DISABLE_MAX_ENDSTOPS) || defined(DISABLE_MIN_ENDSTOPS)
|
||||||
#error "DISABLE_MAX_ENDSTOPS and DISABLE_MIN_ENDSTOPS deprecated. Use individual USE_*_PLUG options instead."
|
#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."
|
|
||||||
#elif defined(LANGUAGE_INCLUDE)
|
#elif defined(LANGUAGE_INCLUDE)
|
||||||
#error "LANGUAGE_INCLUDE has been replaced by LCD_LANGUAGE. Please update your configuration."
|
#error "LANGUAGE_INCLUDE has been replaced by LCD_LANGUAGE. Please update your configuration."
|
||||||
#elif defined(EXTRUDER_OFFSET_X) || defined(EXTRUDER_OFFSET_Y)
|
#elif defined(EXTRUDER_OFFSET_X) || defined(EXTRUDER_OFFSET_Y)
|
||||||
@@ -182,10 +183,12 @@
|
|||||||
#error "MESH_NUM_[XY]_POINTS is now GRID_MAX_POINTS_[XY]. Please update your configuration."
|
#error "MESH_NUM_[XY]_POINTS is now GRID_MAX_POINTS_[XY]. Please update your configuration."
|
||||||
#elif defined(UBL_MESH_NUM_X_POINTS) || defined(UBL_MESH_NUM_Y_POINTS)
|
#elif defined(UBL_MESH_NUM_X_POINTS) || defined(UBL_MESH_NUM_Y_POINTS)
|
||||||
#error "UBL_MESH_NUM_[XY]_POINTS is now GRID_MAX_POINTS_[XY]. Please update your configuration."
|
#error "UBL_MESH_NUM_[XY]_POINTS is now GRID_MAX_POINTS_[XY]. Please update your configuration."
|
||||||
|
#elif defined(UBL_G26_MESH_VALIDATION)
|
||||||
|
#error "UBL_G26_MESH_VALIDATION is now G26_MESH_VALIDATION. Please update your configuration."
|
||||||
#elif defined(UBL_MESH_EDIT_ENABLED)
|
#elif defined(UBL_MESH_EDIT_ENABLED)
|
||||||
#error "UBL_MESH_EDIT_ENABLED is now UBL_G26_MESH_VALIDATION. Please update your configuration."
|
#error "UBL_MESH_EDIT_ENABLED is now G26_MESH_VALIDATION. Please update your configuration."
|
||||||
#elif defined(UBL_MESH_EDITING)
|
#elif defined(UBL_MESH_EDITING)
|
||||||
#error "UBL_MESH_EDITING is now UBL_G26_MESH_VALIDATION. Please update your configuration."
|
#error "UBL_MESH_EDITING is now G26_MESH_VALIDATION. Please update your configuration."
|
||||||
#elif defined(BLTOUCH_HEATERS_OFF)
|
#elif defined(BLTOUCH_HEATERS_OFF)
|
||||||
#error "BLTOUCH_HEATERS_OFF is now PROBING_HEATERS_OFF. Please update your configuration."
|
#error "BLTOUCH_HEATERS_OFF is now PROBING_HEATERS_OFF. Please update your configuration."
|
||||||
#elif defined(BEEPER)
|
#elif defined(BEEPER)
|
||||||
@@ -212,6 +215,24 @@
|
|||||||
#error "ADVANCE was removed in Marlin 1.1.6. Please use LIN_ADVANCE."
|
#error "ADVANCE was removed in Marlin 1.1.6. Please use LIN_ADVANCE."
|
||||||
#elif defined(NEOPIXEL_RGBW_LED)
|
#elif defined(NEOPIXEL_RGBW_LED)
|
||||||
#error "NEOPIXEL_RGBW_LED is now NEOPIXEL_LED. Please update your configuration."
|
#error "NEOPIXEL_RGBW_LED is now NEOPIXEL_LED. Please update your configuration."
|
||||||
|
#elif defined(UBL_MESH_INSET)
|
||||||
|
#error "UBL_MESH_INSET is now just MESH_INSET. Please update your configuration."
|
||||||
|
#elif defined(UBL_MESH_MIN_X) || defined(UBL_MESH_MIN_Y) || defined(UBL_MESH_MAX_X) || defined(UBL_MESH_MAX_Y)
|
||||||
|
#error "UBL_MESH_(MIN|MAX)_[XY] is now just MESH_(MIN|MAX)_[XY]. Please update your configuration."
|
||||||
|
#elif defined(ENABLE_MESH_EDIT_GFX_OVERLAY)
|
||||||
|
#error "ENABLE_MESH_EDIT_GFX_OVERLAY is now MESH_EDIT_GFX_OVERLAY. Please update your configuration."
|
||||||
|
#elif defined(BABYSTEP_ZPROBE_GFX_REVERSE)
|
||||||
|
#error "BABYSTEP_ZPROBE_GFX_REVERSE is now set by OVERLAY_GFX_REVERSE. Please update your configurations."
|
||||||
|
#elif defined(UBL_GRANULAR_SEGMENTATION_FOR_CARTESIAN)
|
||||||
|
#error "UBL_GRANULAR_SEGMENTATION_FOR_CARTESIAN is now SEGMENT_LEVELED_MOVES. Please update your configuration."
|
||||||
|
#elif HAS_PID_HEATING && (defined(K1) || !defined(PID_K1))
|
||||||
|
#error "K1 is now PID_K1. Please update your configuration."
|
||||||
|
#elif defined(PROBE_DOUBLE_TOUCH)
|
||||||
|
#error "PROBE_DOUBLE_TOUCH is now MULTIPLE_PROBING. Please update your configuration."
|
||||||
|
#elif defined(ANET_KEYPAD_LCD)
|
||||||
|
#error "ANET_KEYPAD_LCD is now ZONESTAR_LCD. Please update your configuration."
|
||||||
|
#elif defined(MEASURED_LOWER_LIMIT) || defined(MEASURED_UPPER_LIMIT)
|
||||||
|
#error "MEASURED_(UPPER|LOWER)_LIMIT is now FILWIDTH_ERROR_MARGIN. Please update your configuration."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -235,6 +256,21 @@
|
|||||||
#error "WEBSITE_URL must be specified."
|
#error "WEBSITE_URL must be specified."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Serial
|
||||||
|
*/
|
||||||
|
#ifndef USBCON
|
||||||
|
#if ENABLED(SERIAL_XON_XOFF) && RX_BUFFER_SIZE < 1024
|
||||||
|
#error "SERIAL_XON_XOFF requires RX_BUFFER_SIZE >= 1024 for reliable transfers without drops."
|
||||||
|
#elif RX_BUFFER_SIZE && (RX_BUFFER_SIZE < 2 || !IS_POWER_OF_2(RX_BUFFER_SIZE))
|
||||||
|
#error "RX_BUFFER_SIZE must be a power of 2 greater than 1."
|
||||||
|
#elif TX_BUFFER_SIZE && (TX_BUFFER_SIZE < 2 || TX_BUFFER_SIZE > 256 || !IS_POWER_OF_2(TX_BUFFER_SIZE))
|
||||||
|
#error "TX_BUFFER_SIZE must be 0, a power of 2 greater than 1, and no greater than 256."
|
||||||
|
#endif
|
||||||
|
#elif ENABLED(SERIAL_XON_XOFF)
|
||||||
|
#error "SERIAL_XON_XOFF is not supported on USB-native AVR devices."
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Dual Stepper Drivers
|
* Dual Stepper Drivers
|
||||||
*/
|
*/
|
||||||
@@ -254,17 +290,40 @@
|
|||||||
static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
|
static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
|
||||||
"Movement bounds ([XY]_MIN_POS, [XY]_MAX_POS) are too narrow to contain [XY]_BED_SIZE.");
|
"Movement bounds ([XY]_MIN_POS, [XY]_MAX_POS) are too narrow to contain [XY]_BED_SIZE.");
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Granular software endstops (Marlin >= 1.1.7)
|
||||||
|
*/
|
||||||
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS) && DISABLED(MIN_SOFTWARE_ENDSTOP_Z)
|
||||||
|
#if IS_KINEMATIC
|
||||||
|
#error "MIN_SOFTWARE_ENDSTOPS on DELTA/SCARA also requires MIN_SOFTWARE_ENDSTOP_Z."
|
||||||
|
#elif DISABLED(MIN_SOFTWARE_ENDSTOP_X) && DISABLED(MIN_SOFTWARE_ENDSTOP_Y)
|
||||||
|
#error "MIN_SOFTWARE_ENDSTOPS requires at least one of the MIN_SOFTWARE_ENDSTOP_[XYZ] options."
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS) && DISABLED(MAX_SOFTWARE_ENDSTOP_Z)
|
||||||
|
#if IS_KINEMATIC
|
||||||
|
#error "MAX_SOFTWARE_ENDSTOPS on DELTA/SCARA also requires MAX_SOFTWARE_ENDSTOP_Z."
|
||||||
|
#elif DISABLED(MAX_SOFTWARE_ENDSTOP_X) && DISABLED(MAX_SOFTWARE_ENDSTOP_Y)
|
||||||
|
#error "MAX_SOFTWARE_ENDSTOPS requires at least one of the MAX_SOFTWARE_ENDSTOP_[XYZ] options."
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Progress Bar
|
* Progress Bar
|
||||||
*/
|
*/
|
||||||
#if ENABLED(LCD_PROGRESS_BAR)
|
#if ENABLED(LCD_PROGRESS_BAR)
|
||||||
#if DISABLED(SDSUPPORT)
|
#if DISABLED(SDSUPPORT)
|
||||||
#error "LCD_PROGRESS_BAR requires SDSUPPORT."
|
#error "LCD_PROGRESS_BAR requires SDSUPPORT."
|
||||||
|
#elif DISABLED(ULTRA_LCD)
|
||||||
|
#error "LCD_PROGRESS_BAR requires a character LCD."
|
||||||
#elif ENABLED(DOGLCD)
|
#elif ENABLED(DOGLCD)
|
||||||
#error "LCD_PROGRESS_BAR does not apply to graphical displays."
|
#error "LCD_PROGRESS_BAR does not apply to graphical displays."
|
||||||
#elif ENABLED(FILAMENT_LCD_DISPLAY)
|
#elif ENABLED(FILAMENT_LCD_DISPLAY)
|
||||||
#error "LCD_PROGRESS_BAR and FILAMENT_LCD_DISPLAY are not fully compatible. Comment out this line to use both."
|
#error "LCD_PROGRESS_BAR and FILAMENT_LCD_DISPLAY are not fully compatible. Comment out this line to use both."
|
||||||
#endif
|
#endif
|
||||||
|
#elif ENABLED(LCD_SET_PROGRESS_MANUALLY) && DISABLED(DOGLCD)
|
||||||
|
#error "LCD_SET_PROGRESS_MANUALLY requires LCD_PROGRESS_BAR or Graphical LCD."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -282,6 +341,16 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
|
|||||||
#error "SDSORT_CACHE_NAMES requires SDSORT_USES_RAM (which reads the directory into RAM)."
|
#error "SDSORT_CACHE_NAMES requires SDSORT_USES_RAM (which reads the directory into RAM)."
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(SDSORT_CACHE_NAMES) && DISABLED(SDSORT_DYNAMIC_RAM)
|
||||||
|
#if SDSORT_CACHE_VFATS < 2
|
||||||
|
#error "SDSORT_CACHE_VFATS must be 2 or greater!"
|
||||||
|
#elif SDSORT_CACHE_VFATS > MAX_VFAT_ENTRIES
|
||||||
|
#undef SDSORT_CACHE_VFATS
|
||||||
|
#define SDSORT_CACHE_VFATS MAX_VFAT_ENTRIES
|
||||||
|
#warning "SDSORT_CACHE_VFATS was reduced to MAX_VFAT_ENTRIES!"
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -299,9 +368,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
|
|||||||
* Babystepping
|
* Babystepping
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
#if DISABLED(ULTRA_LCD) && DISABLED(I2C_POSITION_ENCODERS)
|
#if ENABLED(SCARA)
|
||||||
#error "BABYSTEPPING requires an LCD controller."
|
|
||||||
#elif ENABLED(SCARA)
|
|
||||||
#error "BABYSTEPPING is not implemented for SCARA yet."
|
#error "BABYSTEPPING is not implemented for SCARA yet."
|
||||||
#elif ENABLED(DELTA) && ENABLED(BABYSTEP_XY)
|
#elif ENABLED(DELTA) && ENABLED(BABYSTEP_XY)
|
||||||
#error "BABYSTEPPING only implemented for Z axis on deltabots."
|
#error "BABYSTEPPING only implemented for Z axis on deltabots."
|
||||||
@@ -424,6 +491,10 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(LIN_ADVANCE) && !IS_CARTESIAN
|
||||||
|
#error "Sorry! LIN_ADVANCE is only compatible with Cartesian."
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Parking Extruder requirements
|
* Parking Extruder requirements
|
||||||
*/
|
*/
|
||||||
@@ -532,14 +603,14 @@ static_assert(1 >= 0
|
|||||||
* Delta requirements
|
* Delta requirements
|
||||||
*/
|
*/
|
||||||
#if ENABLED(DELTA)
|
#if ENABLED(DELTA)
|
||||||
#if DISABLED(USE_XMAX_PLUG) && DISABLED(USE_YMAX_PLUG) && DISABLED(USE_ZMAX_PLUG)
|
#if HAS_BED_PROBE && ENABLED(Z_MIN_PROBE_ENDSTOP)
|
||||||
|
#error "Delta probably shouldn't use Z_MIN_PROBE_ENDSTOP. Comment out this line to continue."
|
||||||
|
#elif DISABLED(USE_XMAX_PLUG) && DISABLED(USE_YMAX_PLUG) && DISABLED(USE_ZMAX_PLUG)
|
||||||
#error "You probably want to use Max Endstops for DELTA!"
|
#error "You probably want to use Max Endstops for DELTA!"
|
||||||
#elif ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(AUTO_BED_LEVELING_BILINEAR) && !UBL_DELTA
|
#elif ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(AUTO_BED_LEVELING_BILINEAR) && !UBL_SEGMENTED
|
||||||
#error "ENABLE_LEVELING_FADE_HEIGHT on DELTA requires AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL."
|
#error "ENABLE_LEVELING_FADE_HEIGHT on DELTA requires AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL."
|
||||||
#elif ENABLED(DELTA_AUTO_CALIBRATION) && !PROBE_SELECTED
|
#elif ENABLED(DELTA_AUTO_CALIBRATION) && !(HAS_BED_PROBE || ENABLED(ULTIPANEL))
|
||||||
#error "DELTA_AUTO_CALIBRATION requires a probe: PROBE_MANUALLY, FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, Z Servo."
|
#error "DELTA_AUTO_CALIBRATION requires a probe or LCD Controller."
|
||||||
#elif ENABLED(DELTA_AUTO_CALIBRATION) && ENABLED(PROBE_MANUALLY) && DISABLED(ULTIPANEL)
|
|
||||||
#error "DELTA_AUTO_CALIBRATION requires an LCD controller with PROBE_MANUALLY."
|
|
||||||
#elif ABL_GRID
|
#elif ABL_GRID
|
||||||
#if (GRID_MAX_POINTS_X & 1) == 0 || (GRID_MAX_POINTS_Y & 1) == 0
|
#if (GRID_MAX_POINTS_X & 1) == 0 || (GRID_MAX_POINTS_Y & 1) == 0
|
||||||
#error "DELTA requires GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y to be odd numbers."
|
#error "DELTA requires GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y to be odd numbers."
|
||||||
@@ -581,7 +652,7 @@ static_assert(1 >= 0
|
|||||||
, "Please enable only one probe option: PROBE_MANUALLY, FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo."
|
, "Please enable only one probe option: PROBE_MANUALLY, FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo."
|
||||||
);
|
);
|
||||||
|
|
||||||
#if PROBE_SELECTED
|
#if HAS_BED_PROBE
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z_PROBE_SLED is incompatible with DELTA
|
* Z_PROBE_SLED is incompatible with DELTA
|
||||||
@@ -629,14 +700,14 @@ static_assert(1 >= 0
|
|||||||
#if !HAS_Z_MIN_PROBE_PIN
|
#if !HAS_Z_MIN_PROBE_PIN
|
||||||
#error "Z_MIN_PROBE_ENDSTOP requires the Z_MIN_PROBE_PIN to be defined."
|
#error "Z_MIN_PROBE_ENDSTOP requires the Z_MIN_PROBE_PIN to be defined."
|
||||||
#endif
|
#endif
|
||||||
#elif DISABLED(PROBE_MANUALLY)
|
#else
|
||||||
#error "You must enable either Z_MIN_PROBE_ENDSTOP or Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use a probe."
|
#error "You must enable either Z_MIN_PROBE_ENDSTOP or Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use a probe."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Make sure Z raise values are set
|
* Make sure Z raise values are set
|
||||||
*/
|
*/
|
||||||
#if !defined(Z_CLEARANCE_DEPLOY_PROBE)
|
#ifndef Z_CLEARANCE_DEPLOY_PROBE
|
||||||
#error "You must define Z_CLEARANCE_DEPLOY_PROBE in your configuration."
|
#error "You must define Z_CLEARANCE_DEPLOY_PROBE in your configuration."
|
||||||
#elif !defined(Z_CLEARANCE_BETWEEN_PROBES)
|
#elif !defined(Z_CLEARANCE_BETWEEN_PROBES)
|
||||||
#error "You must define Z_CLEARANCE_BETWEEN_PROBES in your configuration."
|
#error "You must define Z_CLEARANCE_BETWEEN_PROBES in your configuration."
|
||||||
@@ -646,19 +717,23 @@ static_assert(1 >= 0
|
|||||||
#error "Probes need Z_CLEARANCE_BETWEEN_PROBES >= 0."
|
#error "Probes need Z_CLEARANCE_BETWEEN_PROBES >= 0."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if MULTIPLE_PROBING && MULTIPLE_PROBING < 2
|
||||||
|
#error "MULTIPLE_PROBING must be >= 2."
|
||||||
|
#endif
|
||||||
|
|
||||||
#else
|
#else
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Require some kind of probe for bed leveling and probe testing
|
* Require some kind of probe for bed leveling and probe testing
|
||||||
*/
|
*/
|
||||||
#if HAS_ABL && DISABLED(AUTO_BED_LEVELING_UBL)
|
#if OLDSCHOOL_ABL && !PROBE_SELECTED
|
||||||
#error "Auto Bed Leveling requires one of these: PROBE_MANUALLY, FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or a Z Servo."
|
#error "Auto Bed Leveling requires one of these: PROBE_MANUALLY, FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or a Z Servo."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif
|
#if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
|
||||||
|
|
||||||
#if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) && !HAS_BED_PROBE
|
|
||||||
#error "Z_MIN_PROBE_REPEATABILITY_TEST requires a probe: FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo."
|
#error "Z_MIN_PROBE_REPEATABILITY_TEST requires a probe: FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo."
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -693,6 +768,9 @@ static_assert(1 >= 0
|
|||||||
* Unified Bed Leveling
|
* Unified Bed Leveling
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
// Hide PROBE_MANUALLY from the rest of the code
|
||||||
|
#undef PROBE_MANUALLY
|
||||||
|
|
||||||
#if IS_SCARA
|
#if IS_SCARA
|
||||||
#error "AUTO_BED_LEVELING_UBL does not yet support SCARA printers."
|
#error "AUTO_BED_LEVELING_UBL does not yet support SCARA printers."
|
||||||
#elif DISABLED(EEPROM_SETTINGS)
|
#elif DISABLED(EEPROM_SETTINGS)
|
||||||
@@ -708,7 +786,7 @@ static_assert(1 >= 0
|
|||||||
static_assert(WITHIN(UBL_PROBE_PT_3_Y, MIN_PROBE_Y, MAX_PROBE_Y), "UBL_PROBE_PT_3_Y can't be reached by the Z probe.");
|
static_assert(WITHIN(UBL_PROBE_PT_3_Y, MIN_PROBE_Y, MAX_PROBE_Y), "UBL_PROBE_PT_3_Y can't be reached by the Z probe.");
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#elif HAS_ABL
|
#elif OLDSCHOOL_ABL
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Auto Bed Leveling
|
* Auto Bed Leveling
|
||||||
@@ -757,26 +835,37 @@ static_assert(1 >= 0
|
|||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
|
// Hide PROBE_MANUALLY from the rest of the code
|
||||||
|
#undef PROBE_MANUALLY
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Mesh Bed Leveling
|
* Mesh Bed Leveling
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#if ENABLED(DELTA)
|
#if ENABLED(DELTA)
|
||||||
#error "MESH_BED_LEVELING does not yet support DELTA printers."
|
#error "MESH_BED_LEVELING is not compatible with DELTA printers."
|
||||||
#elif GRID_MAX_POINTS_X > 9 || GRID_MAX_POINTS_Y > 9
|
#elif GRID_MAX_POINTS_X > 9 || GRID_MAX_POINTS_Y > 9
|
||||||
#error "GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y must be less than 10 for MBL."
|
#error "GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y must be less than 10 for MBL."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if !HAS_MESH && ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#error "G26_MESH_VALIDATION requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_UBL."
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(MESH_EDIT_GFX_OVERLAY) && (DISABLED(AUTO_BED_LEVELING_UBL) || DISABLED(DOGLCD))
|
||||||
|
#error "MESH_EDIT_GFX_OVERLAY requires AUTO_BED_LEVELING_UBL and a Graphical LCD."
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* LCD_BED_LEVELING requirements
|
* LCD_BED_LEVELING requirements
|
||||||
*/
|
*/
|
||||||
#if ENABLED(LCD_BED_LEVELING)
|
#if ENABLED(LCD_BED_LEVELING)
|
||||||
#if DISABLED(ULTIPANEL)
|
#if DISABLED(ULTIPANEL)
|
||||||
#error "LCD_BED_LEVELING requires an LCD controller."
|
#error "LCD_BED_LEVELING requires an LCD controller."
|
||||||
#elif DISABLED(MESH_BED_LEVELING) && !(HAS_ABL && ENABLED(PROBE_MANUALLY))
|
#elif !(ENABLED(MESH_BED_LEVELING) || (OLDSCHOOL_ABL && ENABLED(PROBE_MANUALLY)))
|
||||||
#error "LCD_BED_LEVELING requires MESH_BED_LEVELING or PROBE_MANUALLY with auto bed leveling enabled."
|
#error "LCD_BED_LEVELING requires MESH_BED_LEVELING or ABL with PROBE_MANUALLY."
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -818,8 +907,12 @@ static_assert(1 >= 0
|
|||||||
/**
|
/**
|
||||||
* Filament Width Sensor
|
* Filament Width Sensor
|
||||||
*/
|
*/
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR) && !HAS_FILAMENT_WIDTH_SENSOR
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#if !HAS_FILAMENT_WIDTH_SENSOR
|
||||||
#error "FILAMENT_WIDTH_SENSOR requires a FILWIDTH_PIN to be defined."
|
#error "FILAMENT_WIDTH_SENSOR requires a FILWIDTH_PIN to be defined."
|
||||||
|
#elif ENABLED(NO_VOLUMETRICS)
|
||||||
|
#error "FILAMENT_WIDTH_SENSOR requires NO_VOLUMETRICS to be disabled."
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -915,10 +1008,11 @@ static_assert(1 >= 0
|
|||||||
#error "TEMP_SENSOR_0 is required."
|
#error "TEMP_SENSOR_0 is required."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HOTENDS > 1 || ENABLED(HEATERS_PARALLEL)
|
// Pins are required for heaters
|
||||||
#if !HAS_HEATER_1
|
#if ENABLED(HEATER_0_USES_MAX6675) && !(defined(MAX6675_SS) && MAX6675_SS >= 0)
|
||||||
|
#error "MAX6675_SS (required for TEMP_SENSOR_0) not defined for this board."
|
||||||
|
#elif (HOTENDS > 1 || ENABLED(HEATERS_PARALLEL)) && !HAS_HEATER_1
|
||||||
#error "HEATER_1_PIN not defined for this board."
|
#error "HEATER_1_PIN not defined for this board."
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HOTENDS > 1
|
#if HOTENDS > 1
|
||||||
@@ -1007,42 +1101,45 @@ static_assert(1 >= 0
|
|||||||
/**
|
/**
|
||||||
* Test Extruder Stepper Pins
|
* Test Extruder Stepper Pins
|
||||||
*/
|
*/
|
||||||
#if E_STEPPERS > 4
|
#if DISABLED(MK2_MULTIPLEXER) // MK2_MULTIPLEXER uses E0 stepper only
|
||||||
|
#if E_STEPPERS > 4
|
||||||
#if !PIN_EXISTS(E4_STEP) || !PIN_EXISTS(E4_DIR) || !PIN_EXISTS(E4_ENABLE)
|
#if !PIN_EXISTS(E4_STEP) || !PIN_EXISTS(E4_DIR) || !PIN_EXISTS(E4_ENABLE)
|
||||||
#error "E4_STEP_PIN, E4_DIR_PIN, or E4_ENABLE_PIN not defined for this board."
|
#error "E4_STEP_PIN, E4_DIR_PIN, or E4_ENABLE_PIN not defined for this board."
|
||||||
#endif
|
#endif
|
||||||
#elif E_STEPPERS > 3
|
#elif E_STEPPERS > 3
|
||||||
#if !PIN_EXISTS(E3_STEP) || !PIN_EXISTS(E3_DIR) || !PIN_EXISTS(E3_ENABLE)
|
#if !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."
|
||||||
#endif
|
#endif
|
||||||
#elif E_STEPPERS > 2
|
#elif E_STEPPERS > 2
|
||||||
#if !PIN_EXISTS(E2_STEP) || !PIN_EXISTS(E2_DIR) || !PIN_EXISTS(E2_ENABLE)
|
#if !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."
|
||||||
#endif
|
#endif
|
||||||
#elif E_STEPPERS > 1
|
#elif E_STEPPERS > 1
|
||||||
#if !PIN_EXISTS(E1_STEP) || !PIN_EXISTS(E1_DIR) || !PIN_EXISTS(E1_ENABLE)
|
#if !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."
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
/**
|
||||||
|
* Endstop Tests
|
||||||
|
*/
|
||||||
|
|
||||||
|
#define _PLUG_UNUSED_TEST(AXIS,PLUG) (DISABLED(USE_##PLUG##MIN_PLUG) && DISABLED(USE_##PLUG##MAX_PLUG) && !(ENABLED(AXIS##_DUAL_ENDSTOPS) && WITHIN(AXIS##2_USE_ENDSTOP, _##PLUG##MAX_, _##PLUG##MIN_)))
|
||||||
|
#define _AXIS_PLUG_UNUSED_TEST(AXIS) (_PLUG_UNUSED_TEST(AXIS,X) && _PLUG_UNUSED_TEST(AXIS,Y) && _PLUG_UNUSED_TEST(AXIS,Z))
|
||||||
|
|
||||||
|
// At least 3 endstop plugs must be used
|
||||||
|
#if _AXIS_PLUG_UNUSED_TEST(X)
|
||||||
|
#error "You must enable USE_XMIN_PLUG or USE_XMAX_PLUG."
|
||||||
|
#endif
|
||||||
|
#if _AXIS_PLUG_UNUSED_TEST(Y)
|
||||||
|
#error "You must enable USE_YMIN_PLUG or USE_YMAX_PLUG."
|
||||||
|
#endif
|
||||||
|
#if _AXIS_PLUG_UNUSED_TEST(Z)
|
||||||
|
#error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
// Delta and Cartesian use 3 homing endstops
|
||||||
* Endstops
|
#if !IS_SCARA
|
||||||
*/
|
|
||||||
#if DISABLED(USE_XMIN_PLUG) && DISABLED(USE_XMAX_PLUG) && !(ENABLED(Z_DUAL_ENDSTOPS) && WITHIN(Z2_USE_ENDSTOP, _XMAX_, _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) && WITHIN(Z2_USE_ENDSTOP, _YMAX_, _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) && WITHIN(Z2_USE_ENDSTOP, _ZMAX_, _ZMIN_))
|
|
||||||
#error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG."
|
|
||||||
#elif ENABLED(Z_DUAL_ENDSTOPS)
|
|
||||||
#if !Z2_USE_ENDSTOP
|
|
||||||
#error "You must set Z2_USE_ENDSTOP with Z_DUAL_ENDSTOPS."
|
|
||||||
#elif Z2_MAX_PIN == 0 && Z2_MIN_PIN == 0
|
|
||||||
#error "Z2_USE_ENDSTOP has been assigned to a nonexistent endstop!"
|
|
||||||
#elif ENABLED(DELTA)
|
|
||||||
#error "Z_DUAL_ENDSTOPS is not compatible with DELTA."
|
|
||||||
#endif
|
|
||||||
#elif !IS_SCARA
|
|
||||||
#if X_HOME_DIR < 0 && DISABLED(USE_XMIN_PLUG)
|
#if X_HOME_DIR < 0 && DISABLED(USE_XMIN_PLUG)
|
||||||
#error "Enable USE_XMIN_PLUG when homing X to MIN."
|
#error "Enable USE_XMIN_PLUG when homing X to MIN."
|
||||||
#elif X_HOME_DIR > 0 && DISABLED(USE_XMAX_PLUG)
|
#elif X_HOME_DIR > 0 && DISABLED(USE_XMAX_PLUG)
|
||||||
@@ -1051,10 +1148,76 @@ static_assert(1 >= 0
|
|||||||
#error "Enable USE_YMIN_PLUG when homing Y to MIN."
|
#error "Enable USE_YMIN_PLUG when homing Y to MIN."
|
||||||
#elif Y_HOME_DIR > 0 && DISABLED(USE_YMAX_PLUG)
|
#elif Y_HOME_DIR > 0 && DISABLED(USE_YMAX_PLUG)
|
||||||
#error "Enable USE_YMAX_PLUG when homing Y to MAX."
|
#error "Enable USE_YMAX_PLUG when homing Y to MAX."
|
||||||
#elif Z_HOME_DIR < 0 && DISABLED(USE_ZMIN_PLUG)
|
#endif
|
||||||
|
#endif
|
||||||
|
#if Z_HOME_DIR < 0 && DISABLED(USE_ZMIN_PLUG)
|
||||||
#error "Enable USE_ZMIN_PLUG when homing Z to MIN."
|
#error "Enable USE_ZMIN_PLUG when homing Z to MIN."
|
||||||
#elif Z_HOME_DIR > 0 && DISABLED(USE_ZMAX_PLUG)
|
#elif Z_HOME_DIR > 0 && DISABLED(USE_ZMAX_PLUG)
|
||||||
#error "Enable USE_ZMAX_PLUG when homing Z to MAX."
|
#error "Enable USE_ZMAX_PLUG when homing Z to MAX."
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Dual endstops requirements
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#if !X2_USE_ENDSTOP
|
||||||
|
#error "You must set X2_USE_ENDSTOP with X_DUAL_ENDSTOPS."
|
||||||
|
#elif X2_USE_ENDSTOP == _X_MIN_ && DISABLED(USE_XMIN_PLUG)
|
||||||
|
#error "USE_XMIN_PLUG is required when X2_USE_ENDSTOP is _X_MIN_."
|
||||||
|
#elif X2_USE_ENDSTOP == _X_MAX_ && DISABLED(USE_XMAX_PLUG)
|
||||||
|
#error "USE_XMAX_PLUG is required when X2_USE_ENDSTOP is _X_MAX_."
|
||||||
|
#elif X2_USE_ENDSTOP == _Y_MIN_ && DISABLED(USE_YMIN_PLUG)
|
||||||
|
#error "USE_YMIN_PLUG is required when X2_USE_ENDSTOP is _Y_MIN_."
|
||||||
|
#elif X2_USE_ENDSTOP == _Y_MAX_ && DISABLED(USE_YMAX_PLUG)
|
||||||
|
#error "USE_YMAX_PLUG is required when X2_USE_ENDSTOP is _Y_MAX_."
|
||||||
|
#elif X2_USE_ENDSTOP == _Z_MIN_ && DISABLED(USE_ZMIN_PLUG)
|
||||||
|
#error "USE_ZMIN_PLUG is required when X2_USE_ENDSTOP is _Z_MIN_."
|
||||||
|
#elif X2_USE_ENDSTOP == _Z_MAX_ && DISABLED(USE_ZMAX_PLUG)
|
||||||
|
#error "USE_ZMAX_PLUG is required when X2_USE_ENDSTOP is _Z_MAX_."
|
||||||
|
#elif !HAS_X2_MIN && !HAS_X2_MAX
|
||||||
|
#error "X2_USE_ENDSTOP has been assigned to a nonexistent endstop!"
|
||||||
|
#elif ENABLED(DELTA)
|
||||||
|
#error "X_DUAL_ENDSTOPS is not compatible with DELTA."
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#if !Y2_USE_ENDSTOP
|
||||||
|
#error "You must set Y2_USE_ENDSTOP with Y_DUAL_ENDSTOPS."
|
||||||
|
#elif Y2_USE_ENDSTOP == _X_MIN_ && DISABLED(USE_XMIN_PLUG)
|
||||||
|
#error "USE_XMIN_PLUG is required when Y2_USE_ENDSTOP is _X_MIN_."
|
||||||
|
#elif Y2_USE_ENDSTOP == _X_MAX_ && DISABLED(USE_XMAX_PLUG)
|
||||||
|
#error "USE_XMAX_PLUG is required when Y2_USE_ENDSTOP is _X_MAX_."
|
||||||
|
#elif Y2_USE_ENDSTOP == _Y_MIN_ && DISABLED(USE_YMIN_PLUG)
|
||||||
|
#error "USE_YMIN_PLUG is required when Y2_USE_ENDSTOP is _Y_MIN_."
|
||||||
|
#elif Y2_USE_ENDSTOP == _Y_MAX_ && DISABLED(USE_YMAX_PLUG)
|
||||||
|
#error "USE_YMAX_PLUG is required when Y2_USE_ENDSTOP is _Y_MAX_."
|
||||||
|
#elif Y2_USE_ENDSTOP == _Z_MIN_ && DISABLED(USE_ZMIN_PLUG)
|
||||||
|
#error "USE_ZMIN_PLUG is required when Y2_USE_ENDSTOP is _Z_MIN_."
|
||||||
|
#elif Y2_USE_ENDSTOP == _Z_MAX_ && DISABLED(USE_ZMAX_PLUG)
|
||||||
|
#error "USE_ZMAX_PLUG is required when Y2_USE_ENDSTOP is _Z_MAX_."
|
||||||
|
#elif !HAS_Y2_MIN && !HAS_Y2_MAX
|
||||||
|
#error "Y2_USE_ENDSTOP has been assigned to a nonexistent endstop!"
|
||||||
|
#elif ENABLED(DELTA)
|
||||||
|
#error "Y_DUAL_ENDSTOPS is not compatible with DELTA."
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
|
#if !Z2_USE_ENDSTOP
|
||||||
|
#error "You must set Z2_USE_ENDSTOP with Z_DUAL_ENDSTOPS."
|
||||||
|
#elif Z2_USE_ENDSTOP == _X_MIN_ && DISABLED(USE_XMIN_PLUG)
|
||||||
|
#error "USE_XMIN_PLUG is required when Z2_USE_ENDSTOP is _X_MIN_."
|
||||||
|
#elif Z2_USE_ENDSTOP == _X_MAX_ && DISABLED(USE_XMAX_PLUG)
|
||||||
|
#error "USE_XMAX_PLUG is required when Z2_USE_ENDSTOP is _X_MAX_."
|
||||||
|
#elif Z2_USE_ENDSTOP == _Y_MIN_ && DISABLED(USE_YMIN_PLUG)
|
||||||
|
#error "USE_YMIN_PLUG is required when Z2_USE_ENDSTOP is _Y_MIN_."
|
||||||
|
#elif Z2_USE_ENDSTOP == _Y_MAX_ && DISABLED(USE_YMAX_PLUG)
|
||||||
|
#error "USE_YMAX_PLUG is required when Z2_USE_ENDSTOP is _Y_MAX_."
|
||||||
|
#elif Z2_USE_ENDSTOP == _Z_MIN_ && DISABLED(USE_ZMIN_PLUG)
|
||||||
|
#error "USE_ZMIN_PLUG is required when Z2_USE_ENDSTOP is _Z_MIN_."
|
||||||
|
#elif Z2_USE_ENDSTOP == _Z_MAX_ && DISABLED(USE_ZMAX_PLUG)
|
||||||
|
#error "USE_ZMAX_PLUG is required when Z2_USE_ENDSTOP is _Z_MAX_."
|
||||||
|
#elif !HAS_Z2_MIN && !HAS_Z2_MAX
|
||||||
|
#error "Z2_USE_ENDSTOP has been assigned to a nonexistent endstop!"
|
||||||
|
#elif ENABLED(DELTA)
|
||||||
|
#error "Z_DUAL_ENDSTOPS is not compatible with DELTA."
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1132,6 +1295,7 @@ static_assert(1 >= 0
|
|||||||
* REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER => REPRAP_DISCOUNT_SMART_CONTROLLER
|
* REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER => REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||||
* SAV_3DGLCD => U8GLIB_SH1106 => ULTIMAKERCONTROLLER
|
* SAV_3DGLCD => U8GLIB_SH1106 => ULTIMAKERCONTROLLER
|
||||||
* MKS_12864OLED => U8GLIB_SH1106 => ULTIMAKERCONTROLLER
|
* MKS_12864OLED => U8GLIB_SH1106 => ULTIMAKERCONTROLLER
|
||||||
|
* MKS_12864OLED_SSD1306 => U8GLIB_SSD1306 => ULTIMAKERCONTROLLER
|
||||||
* miniVIKI => ULTIMAKERCONTROLLER
|
* miniVIKI => ULTIMAKERCONTROLLER
|
||||||
* VIKI2 => ULTIMAKERCONTROLLER
|
* VIKI2 => ULTIMAKERCONTROLLER
|
||||||
* ELB_FULL_GRAPHIC_CONTROLLER => ULTIMAKERCONTROLLER
|
* ELB_FULL_GRAPHIC_CONTROLLER => ULTIMAKERCONTROLLER
|
||||||
@@ -1144,14 +1308,16 @@ static_assert(1 >= 0
|
|||||||
&& DISABLED(VIKI2) \
|
&& DISABLED(VIKI2) \
|
||||||
&& DISABLED(ELB_FULL_GRAPHIC_CONTROLLER) \
|
&& DISABLED(ELB_FULL_GRAPHIC_CONTROLLER) \
|
||||||
&& DISABLED(PANEL_ONE) \
|
&& DISABLED(PANEL_ONE) \
|
||||||
&& DISABLED(MKS_12864OLED)
|
&& DISABLED(MKS_12864OLED) \
|
||||||
|
&& DISABLED(MKS_12864OLED_SSD1306)
|
||||||
+ 1
|
+ 1
|
||||||
#endif
|
#endif
|
||||||
#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) \
|
#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) \
|
||||||
&& DISABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) \
|
&& DISABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) \
|
||||||
&& DISABLED(LCD_FOR_MELZI) \
|
&& DISABLED(LCD_FOR_MELZI) \
|
||||||
&& DISABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602) \
|
&& DISABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602) \
|
||||||
&& DISABLED(MKS_12864OLED)
|
&& DISABLED(MKS_12864OLED) \
|
||||||
|
&& DISABLED(MKS_12864OLED_SSD1306)
|
||||||
+ 1
|
+ 1
|
||||||
#endif
|
#endif
|
||||||
#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) \
|
#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) \
|
||||||
@@ -1164,6 +1330,9 @@ static_assert(1 >= 0
|
|||||||
#if ENABLED(MKS_12864OLED)
|
#if ENABLED(MKS_12864OLED)
|
||||||
+ 1
|
+ 1
|
||||||
#endif
|
#endif
|
||||||
|
#if ENABLED(MKS_12864OLED_SSD1306)
|
||||||
|
+ 1
|
||||||
|
#endif
|
||||||
#if ENABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602)
|
#if ENABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602)
|
||||||
+ 1
|
+ 1
|
||||||
#endif
|
#endif
|
||||||
@@ -1199,7 +1368,7 @@ static_assert(1 >= 0
|
|||||||
#endif
|
#endif
|
||||||
#if ENABLED(REPRAPWORLD_KEYPAD) \
|
#if ENABLED(REPRAPWORLD_KEYPAD) \
|
||||||
&& DISABLED(CARTESIO_UI) \
|
&& DISABLED(CARTESIO_UI) \
|
||||||
&& DISABLED(ANET_KEYPAD_LCD)
|
&& DISABLED(ZONESTAR_LCD)
|
||||||
+ 1
|
+ 1
|
||||||
#endif
|
#endif
|
||||||
#if ENABLED(RIGIDBOT_PANEL)
|
#if ENABLED(RIGIDBOT_PANEL)
|
||||||
@@ -1220,7 +1389,7 @@ static_assert(1 >= 0
|
|||||||
#if ENABLED(LCD_I2C_VIKI)
|
#if ENABLED(LCD_I2C_VIKI)
|
||||||
+ 1
|
+ 1
|
||||||
#endif
|
#endif
|
||||||
#if ENABLED(U8GLIB_SSD1306) && DISABLED(OLED_PANEL_TINYBOY2)
|
#if ENABLED(U8GLIB_SSD1306) && DISABLED(OLED_PANEL_TINYBOY2) && DISABLED(MKS_12864OLED_SSD1306)
|
||||||
+ 1
|
+ 1
|
||||||
#endif
|
#endif
|
||||||
#if ENABLED(SAV_3DLCD)
|
#if ENABLED(SAV_3DLCD)
|
||||||
@@ -1235,7 +1404,7 @@ static_assert(1 >= 0
|
|||||||
#if ENABLED(OLED_PANEL_TINYBOY2)
|
#if ENABLED(OLED_PANEL_TINYBOY2)
|
||||||
+ 1
|
+ 1
|
||||||
#endif
|
#endif
|
||||||
#if ENABLED(ANET_KEYPAD_LCD)
|
#if ENABLED(ZONESTAR_LCD)
|
||||||
+ 1
|
+ 1
|
||||||
#endif
|
#endif
|
||||||
, "Please select no more than one LCD controller option."
|
, "Please select no more than one LCD controller option."
|
||||||
@@ -1274,14 +1443,37 @@ static_assert(1 >= 0
|
|||||||
|| ENABLED( E1_IS_TMC2130 ) \
|
|| ENABLED( E1_IS_TMC2130 ) \
|
||||||
|| ENABLED( E2_IS_TMC2130 ) \
|
|| ENABLED( E2_IS_TMC2130 ) \
|
||||||
|| ENABLED( E3_IS_TMC2130 ) \
|
|| ENABLED( E3_IS_TMC2130 ) \
|
||||||
|| ENABLED( E4_IS_TMC2130 ) \
|
|| ENABLED( E4_IS_TMC2130 ) )
|
||||||
)
|
|
||||||
#error "HAVE_TMC2130 requires at least one TMC2130 stepper to be set."
|
#error "HAVE_TMC2130 requires at least one TMC2130 stepper to be set."
|
||||||
#elif ENABLED(HYBRID_THRESHOLD) && DISABLED(STEALTHCHOP)
|
#elif ENABLED(HYBRID_THRESHOLD) && DISABLED(STEALTHCHOP)
|
||||||
#error "Enable STEALTHCHOP to use HYBRID_THRESHOLD."
|
#error "Enable STEALTHCHOP to use HYBRID_THRESHOLD."
|
||||||
|
#elif defined(AUTOMATIC_CURRENT_CONTROL)
|
||||||
|
#error "AUTOMATIC_CURRENT_CONTROL is now MONITOR_DRIVER_STATUS. Please update your configuration."
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Make sure HAVE_TMC2208 is warranted
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2208) && !( \
|
||||||
|
ENABLED( X_IS_TMC2208 ) \
|
||||||
|
|| ENABLED( X2_IS_TMC2208 ) \
|
||||||
|
|| ENABLED( Y_IS_TMC2208 ) \
|
||||||
|
|| ENABLED( Y2_IS_TMC2208 ) \
|
||||||
|
|| ENABLED( Z_IS_TMC2208 ) \
|
||||||
|
|| ENABLED( Z2_IS_TMC2208 ) \
|
||||||
|
|| ENABLED( E0_IS_TMC2208 ) \
|
||||||
|
|| ENABLED( E1_IS_TMC2208 ) \
|
||||||
|
|| ENABLED( E2_IS_TMC2208 ) \
|
||||||
|
|| ENABLED( E3_IS_TMC2208 ) )
|
||||||
|
#error "HAVE_TMC2208 requires at least one TMC2208 stepper to be set."
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(HYBRID_THRESHOLD) && DISABLED(STEALTHCHOP)
|
||||||
|
#error "Enable STEALTHCHOP to use HYBRID_THRESHOLD."
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Make sure HAVE_L6470DRIVER is warranted
|
* Make sure HAVE_L6470DRIVER is warranted
|
||||||
*/
|
*/
|
||||||
@@ -1384,3 +1576,31 @@ static_assert(COUNT(sanity_arr_3) <= XYZE_N, "DEFAULT_MAX_ACCELERATION has too m
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#endif // SPINDLE_LASER_ENABLE
|
#endif // SPINDLE_LASER_ENABLE
|
||||||
|
|
||||||
|
#if ENABLED(CNC_COORDINATE_SYSTEMS) && ENABLED(NO_WORKSPACE_OFFSETS)
|
||||||
|
#error "CNC_COORDINATE_SYSTEMS is incompatible with NO_WORKSPACE_OFFSETS."
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if !BLOCK_BUFFER_SIZE || !IS_POWER_OF_2(BLOCK_BUFFER_SIZE)
|
||||||
|
#error "BLOCK_BUFFER_SIZE must be a power of 2."
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(LED_CONTROL_MENU) && DISABLED(ULTIPANEL)
|
||||||
|
#error "LED_CONTROL_MENU requires an LCD controller."
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
#if !defined(XY_SKEW_FACTOR) && !(defined(XY_DIAG_AC) && defined(XY_DIAG_BD) && defined(XY_SIDE_AD))
|
||||||
|
#error "SKEW_CORRECTION requires XY_SKEW_FACTOR or XY_DIAG_AC, XY_DIAG_BD, XY_SIDE_AD."
|
||||||
|
#endif
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#if !defined(XZ_SKEW_FACTOR) && !(defined(XZ_DIAG_AC) && defined(XZ_DIAG_BD) && defined(XZ_SIDE_AD))
|
||||||
|
#error "SKEW_CORRECTION requires XZ_SKEW_FACTOR or XZ_DIAG_AC, XZ_DIAG_BD, XZ_SIDE_AD."
|
||||||
|
#endif
|
||||||
|
#if !defined(YZ_SKEW_FACTOR) && !(defined(YZ_DIAG_AC) && defined(YZ_DIAG_BD) && defined(YZ_SIDE_AD))
|
||||||
|
#error "SKEW_CORRECTION requires YZ_SKEW_FACTOR or YZ_DIAG_AC, YZ_DIAG_BD, YZ_SIDE_AD."
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // _SANITYCHECK_H_
|
||||||
|
|||||||
@@ -26,19 +26,19 @@
|
|||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#include "MarlinConfig.h"
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
#include "Sd2Card.h"
|
#include "Sd2Card.h"
|
||||||
|
|
||||||
#if ENABLED(USE_WATCHDOG)
|
#if ENABLED(USE_WATCHDOG)
|
||||||
#include "watchdog.h"
|
#include "watchdog.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
#if DISABLED(SOFTWARE_SPI)
|
#if DISABLED(SOFTWARE_SPI)
|
||||||
// functions for hardware SPI
|
// functions for hardware SPI
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// make sure SPCR rate is in expected bits
|
// make sure SPCR rate is in expected bits
|
||||||
#if (SPR0 != 0 || SPR1 != 1)
|
#if (SPR0 != 0 || SPR1 != 1)
|
||||||
#error "unexpected SPCR bits"
|
#error "unexpected SPCR bits"
|
||||||
@@ -52,14 +52,14 @@
|
|||||||
SPCR = _BV(SPE) | _BV(MSTR) | (spiRate >> 1);
|
SPCR = _BV(SPE) | _BV(MSTR) | (spiRate >> 1);
|
||||||
SPSR = spiRate & 1 || spiRate == 6 ? 0 : _BV(SPI2X);
|
SPSR = spiRate & 1 || spiRate == 6 ? 0 : _BV(SPI2X);
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** SPI receive a byte */
|
/** SPI receive a byte */
|
||||||
static uint8_t spiRec() {
|
static uint8_t spiRec() {
|
||||||
SPDR = 0xFF;
|
SPDR = 0xFF;
|
||||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||||
return SPDR;
|
return SPDR;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** SPI read data - only one call so force inline */
|
/** SPI read data - only one call so force inline */
|
||||||
static inline __attribute__((always_inline))
|
static inline __attribute__((always_inline))
|
||||||
void spiRead(uint8_t* buf, uint16_t nbyte) {
|
void spiRead(uint8_t* buf, uint16_t nbyte) {
|
||||||
@@ -73,13 +73,13 @@
|
|||||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||||
buf[nbyte] = SPDR;
|
buf[nbyte] = SPDR;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** SPI send a byte */
|
/** SPI send a byte */
|
||||||
static void spiSend(uint8_t b) {
|
static void spiSend(uint8_t b) {
|
||||||
SPDR = b;
|
SPDR = b;
|
||||||
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ }
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** SPI send block - only one call so force inline */
|
/** SPI send block - only one call so force inline */
|
||||||
static inline __attribute__((always_inline))
|
static inline __attribute__((always_inline))
|
||||||
void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
||||||
@@ -95,9 +95,10 @@
|
|||||||
//------------------------------------------------------------------------------
|
//------------------------------------------------------------------------------
|
||||||
#else // SOFTWARE_SPI
|
#else // SOFTWARE_SPI
|
||||||
//------------------------------------------------------------------------------
|
//------------------------------------------------------------------------------
|
||||||
|
|
||||||
/** nop to tune soft SPI timing */
|
/** nop to tune soft SPI timing */
|
||||||
#define nop asm volatile ("nop\n\t")
|
#define nop asm volatile ("nop\n\t")
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Soft SPI receive byte */
|
/** Soft SPI receive byte */
|
||||||
static uint8_t spiRec() {
|
static uint8_t spiRec() {
|
||||||
uint8_t data = 0;
|
uint8_t data = 0;
|
||||||
@@ -123,13 +124,13 @@
|
|||||||
sei();
|
sei();
|
||||||
return data;
|
return data;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Soft SPI read data */
|
/** Soft SPI read data */
|
||||||
static void spiRead(uint8_t* buf, uint16_t nbyte) {
|
static void spiRead(uint8_t* buf, uint16_t nbyte) {
|
||||||
for (uint16_t i = 0; i < nbyte; i++)
|
for (uint16_t i = 0; i < nbyte; i++)
|
||||||
buf[i] = spiRec();
|
buf[i] = spiRec();
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Soft SPI send byte */
|
/** Soft SPI send byte */
|
||||||
static void spiSend(uint8_t data) {
|
static void spiSend(uint8_t data) {
|
||||||
// no interrupts during byte send - about 8 us
|
// no interrupts during byte send - about 8 us
|
||||||
@@ -153,7 +154,7 @@
|
|||||||
// enable interrupts
|
// enable interrupts
|
||||||
sei();
|
sei();
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Soft SPI send block */
|
/** Soft SPI send block */
|
||||||
void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
void spiSendBlock(uint8_t token, const uint8_t* buf) {
|
||||||
spiSend(token);
|
spiSend(token);
|
||||||
@@ -161,7 +162,7 @@
|
|||||||
spiSend(buf[i]);
|
spiSend(buf[i]);
|
||||||
}
|
}
|
||||||
#endif // SOFTWARE_SPI
|
#endif // SOFTWARE_SPI
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// send command and return error code. Return zero for OK
|
// send command and return error code. Return zero for OK
|
||||||
uint8_t Sd2Card::cardCommand(uint8_t cmd, uint32_t arg) {
|
uint8_t Sd2Card::cardCommand(uint8_t cmd, uint32_t arg) {
|
||||||
// select card
|
// select card
|
||||||
@@ -189,7 +190,7 @@ uint8_t Sd2Card::cardCommand(uint8_t cmd, uint32_t arg) {
|
|||||||
for (uint8_t i = 0; ((status_ = spiRec()) & 0x80) && i != 0xFF; i++) { /* Intentionally left empty */ }
|
for (uint8_t i = 0; ((status_ = spiRec()) & 0x80) && i != 0xFF; i++) { /* Intentionally left empty */ }
|
||||||
return status_;
|
return status_;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* Determine the size of an SD flash memory card.
|
* Determine the size of an SD flash memory card.
|
||||||
*
|
*
|
||||||
@@ -217,19 +218,20 @@ uint32_t Sd2Card::cardSize() {
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
void Sd2Card::chipSelectHigh() {
|
void Sd2Card::chipSelectHigh() {
|
||||||
digitalWrite(chipSelectPin_, HIGH);
|
digitalWrite(chipSelectPin_, HIGH);
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
void Sd2Card::chipSelectLow() {
|
void Sd2Card::chipSelectLow() {
|
||||||
#if DISABLED(SOFTWARE_SPI)
|
#if DISABLED(SOFTWARE_SPI)
|
||||||
spiInit(spiRate_);
|
spiInit(spiRate_);
|
||||||
#endif // SOFTWARE_SPI
|
#endif // SOFTWARE_SPI
|
||||||
digitalWrite(chipSelectPin_, LOW);
|
digitalWrite(chipSelectPin_, LOW);
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Erase a range of blocks.
|
/**
|
||||||
|
* Erase a range of blocks.
|
||||||
*
|
*
|
||||||
* \param[in] firstBlock The address of the first block in the range.
|
* \param[in] firstBlock The address of the first block in the range.
|
||||||
* \param[in] lastBlock The address of the last block in the range.
|
* \param[in] lastBlock The address of the last block in the range.
|
||||||
@@ -239,8 +241,7 @@ void Sd2Card::chipSelectLow() {
|
|||||||
* either 0 or 1, depends on the card vendor. The card must support
|
* either 0 or 1, depends on the card vendor. The card must support
|
||||||
* single block erase.
|
* single block erase.
|
||||||
*
|
*
|
||||||
* \return The value one, true, is returned for success and
|
* \return true for success, false for failure.
|
||||||
* the value zero, false, is returned for failure.
|
|
||||||
*/
|
*/
|
||||||
bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) {
|
bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) {
|
||||||
csd_t csd;
|
csd_t csd;
|
||||||
@@ -275,26 +276,26 @@ bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) {
|
|||||||
chipSelectHigh();
|
chipSelectHigh();
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Determine if card supports single block erase.
|
/**
|
||||||
|
* Determine if card supports single block erase.
|
||||||
*
|
*
|
||||||
* \return The value one, true, is returned if single block erase is supported.
|
* \return true if single block erase is supported.
|
||||||
* The value zero, false, is returned if single block erase is not supported.
|
* false if single block erase is not supported.
|
||||||
*/
|
*/
|
||||||
bool Sd2Card::eraseSingleBlockEnable() {
|
bool Sd2Card::eraseSingleBlockEnable() {
|
||||||
csd_t csd;
|
csd_t csd;
|
||||||
return readCSD(&csd) ? csd.v1.erase_blk_en : false;
|
return readCSD(&csd) ? csd.v1.erase_blk_en : false;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* Initialize an SD flash memory card.
|
* Initialize an SD flash memory card.
|
||||||
*
|
*
|
||||||
* \param[in] sckRateID SPI clock rate selector. See setSckRate().
|
* \param[in] sckRateID SPI clock rate selector. See setSckRate().
|
||||||
* \param[in] chipSelectPin SD chip select pin number.
|
* \param[in] chipSelectPin SD chip select pin number.
|
||||||
*
|
*
|
||||||
* \return The value one, true, is returned for success and
|
* \return true for success, false for failure.
|
||||||
* the value zero, false, is returned for failure. The reason for failure
|
* The reason for failure can be determined by calling errorCode() and errorData().
|
||||||
* can be determined by calling errorCode() and errorData().
|
|
||||||
*/
|
*/
|
||||||
bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
|
bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
|
||||||
errorCode_ = type_ = 0;
|
errorCode_ = type_ = 0;
|
||||||
@@ -384,14 +385,13 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
|
|||||||
chipSelectHigh();
|
chipSelectHigh();
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* Read a 512 byte block from an SD card.
|
* Read a 512 byte block from an SD card.
|
||||||
*
|
*
|
||||||
* \param[in] blockNumber Logical block to be read.
|
* \param[in] blockNumber Logical block to be read.
|
||||||
* \param[out] dst Pointer to the location that will receive the data.
|
* \param[out] dst Pointer to the location that will receive the data.
|
||||||
* \return The value one, true, is returned for success and
|
* \return true for success, false for failure.
|
||||||
* the value zero, false, is returned for failure.
|
|
||||||
*/
|
*/
|
||||||
bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) {
|
bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) {
|
||||||
// use address if not SDHC card
|
// use address if not SDHC card
|
||||||
@@ -399,19 +399,18 @@ bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) {
|
|||||||
|
|
||||||
#if ENABLED(SD_CHECK_AND_RETRY)
|
#if ENABLED(SD_CHECK_AND_RETRY)
|
||||||
uint8_t retryCnt = 3;
|
uint8_t retryCnt = 3;
|
||||||
do {
|
for(;;) {
|
||||||
if (!cardCommand(CMD17, blockNumber)) {
|
if (cardCommand(CMD17, blockNumber))
|
||||||
if (readData(dst, 512)) return true;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
error(SD_CARD_ERROR_CMD17);
|
error(SD_CARD_ERROR_CMD17);
|
||||||
|
else if (readData(dst, 512))
|
||||||
|
return true;
|
||||||
|
|
||||||
if (!--retryCnt) break;
|
if (!--retryCnt) break;
|
||||||
|
|
||||||
chipSelectHigh();
|
chipSelectHigh();
|
||||||
cardCommand(CMD12, 0); // Try sending a stop command, ignore the result.
|
cardCommand(CMD12, 0); // Try sending a stop command, ignore the result.
|
||||||
errorCode_ = 0;
|
errorCode_ = 0;
|
||||||
} while (true);
|
}
|
||||||
#else
|
#else
|
||||||
if (cardCommand(CMD17, blockNumber))
|
if (cardCommand(CMD17, blockNumber))
|
||||||
error(SD_CARD_ERROR_CMD17);
|
error(SD_CARD_ERROR_CMD17);
|
||||||
@@ -422,13 +421,13 @@ bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) {
|
|||||||
chipSelectHigh();
|
chipSelectHigh();
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Read one data block in a multiple block read sequence
|
/**
|
||||||
|
* Read one data block in a multiple block read sequence
|
||||||
*
|
*
|
||||||
* \param[in] dst Pointer to the location for the data to be read.
|
* \param[in] dst Pointer to the location for the data to be read.
|
||||||
*
|
*
|
||||||
* \return The value one, true, is returned for success and
|
* \return true for success, false for failure.
|
||||||
* the value zero, false, is returned for failure.
|
|
||||||
*/
|
*/
|
||||||
bool Sd2Card::readData(uint8_t* dst) {
|
bool Sd2Card::readData(uint8_t* dst) {
|
||||||
chipSelectLow();
|
chipSelectLow();
|
||||||
@@ -436,7 +435,7 @@ bool Sd2Card::readData(uint8_t* dst) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
#if ENABLED(SD_CHECK_AND_RETRY)
|
#if ENABLED(SD_CHECK_AND_RETRY)
|
||||||
static const uint16_t crctab[] PROGMEM = {
|
static const uint16_t crctab[] PROGMEM = {
|
||||||
0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7,
|
0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7,
|
||||||
0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF,
|
0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF,
|
||||||
0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6,
|
0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6,
|
||||||
@@ -469,17 +468,16 @@ static const uint16_t crctab[] PROGMEM = {
|
|||||||
0x7C26, 0x6C07, 0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1,
|
0x7C26, 0x6C07, 0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1,
|
||||||
0xEF1F, 0xFF3E, 0xCF5D, 0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8,
|
0xEF1F, 0xFF3E, 0xCF5D, 0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8,
|
||||||
0x6E17, 0x7E36, 0x4E55, 0x5E74, 0x2E93, 0x3EB2, 0x0ED1, 0x1EF0
|
0x6E17, 0x7E36, 0x4E55, 0x5E74, 0x2E93, 0x3EB2, 0x0ED1, 0x1EF0
|
||||||
};
|
};
|
||||||
static uint16_t CRC_CCITT(const uint8_t* data, size_t n) {
|
static uint16_t CRC_CCITT(const uint8_t* data, size_t n) {
|
||||||
uint16_t crc = 0;
|
uint16_t crc = 0;
|
||||||
for (size_t i = 0; i < n; i++) {
|
for (size_t i = 0; i < n; i++) {
|
||||||
crc = pgm_read_word(&crctab[(crc >> 8 ^ data[i]) & 0xFF]) ^ (crc << 8);
|
crc = pgm_read_word(&crctab[(crc >> 8 ^ data[i]) & 0xFF]) ^ (crc << 8);
|
||||||
}
|
}
|
||||||
return crc;
|
return crc;
|
||||||
}
|
}
|
||||||
#endif
|
#endif // SD_CHECK_AND_RETRY
|
||||||
|
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
bool Sd2Card::readData(uint8_t* dst, uint16_t count) {
|
bool Sd2Card::readData(uint8_t* dst, uint16_t count) {
|
||||||
// wait for start block token
|
// wait for start block token
|
||||||
uint16_t t0 = millis();
|
uint16_t t0 = millis();
|
||||||
@@ -521,61 +519,55 @@ bool Sd2Card::readData(uint8_t* dst, uint16_t count) {
|
|||||||
spiSend(0XFF);
|
spiSend(0XFF);
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** read CID or CSR register */
|
/** read CID or CSR register */
|
||||||
bool Sd2Card::readRegister(uint8_t cmd, void* buf) {
|
bool Sd2Card::readRegister(uint8_t cmd, void* buf) {
|
||||||
uint8_t* dst = reinterpret_cast<uint8_t*>(buf);
|
uint8_t* dst = reinterpret_cast<uint8_t*>(buf);
|
||||||
if (cardCommand(cmd, 0)) {
|
if (cardCommand(cmd, 0)) {
|
||||||
error(SD_CARD_ERROR_READ_REG);
|
error(SD_CARD_ERROR_READ_REG);
|
||||||
goto FAIL;
|
|
||||||
}
|
|
||||||
return readData(dst, 16);
|
|
||||||
FAIL:
|
|
||||||
chipSelectHigh();
|
chipSelectHigh();
|
||||||
return false;
|
return false;
|
||||||
|
}
|
||||||
|
return readData(dst, 16);
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Start a read multiple blocks sequence.
|
/**
|
||||||
|
* Start a read multiple blocks sequence.
|
||||||
*
|
*
|
||||||
* \param[in] blockNumber Address of first block in sequence.
|
* \param[in] blockNumber Address of first block in sequence.
|
||||||
*
|
*
|
||||||
* \note This function is used with readData() and readStop() for optimized
|
* \note This function is used with readData() and readStop() for optimized
|
||||||
* multiple block reads. SPI chipSelect must be low for the entire sequence.
|
* multiple block reads. SPI chipSelect must be low for the entire sequence.
|
||||||
*
|
*
|
||||||
* \return The value one, true, is returned for success and
|
* \return true for success, false for failure.
|
||||||
* the value zero, false, is returned for failure.
|
|
||||||
*/
|
*/
|
||||||
bool Sd2Card::readStart(uint32_t blockNumber) {
|
bool Sd2Card::readStart(uint32_t blockNumber) {
|
||||||
if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9;
|
if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9;
|
||||||
if (cardCommand(CMD18, blockNumber)) {
|
if (cardCommand(CMD18, blockNumber)) {
|
||||||
error(SD_CARD_ERROR_CMD18);
|
error(SD_CARD_ERROR_CMD18);
|
||||||
goto FAIL;
|
chipSelectHigh();
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
chipSelectHigh();
|
chipSelectHigh();
|
||||||
return true;
|
return true;
|
||||||
FAIL:
|
|
||||||
chipSelectHigh();
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** End a read multiple blocks sequence.
|
/**
|
||||||
|
* End a read multiple blocks sequence.
|
||||||
*
|
*
|
||||||
* \return The value one, true, is returned for success and
|
* \return true for success, false for failure.
|
||||||
* the value zero, false, is returned for failure.
|
|
||||||
*/
|
*/
|
||||||
bool Sd2Card::readStop() {
|
bool Sd2Card::readStop() {
|
||||||
chipSelectLow();
|
chipSelectLow();
|
||||||
if (cardCommand(CMD12, 0)) {
|
if (cardCommand(CMD12, 0)) {
|
||||||
error(SD_CARD_ERROR_CMD12);
|
error(SD_CARD_ERROR_CMD12);
|
||||||
goto FAIL;
|
chipSelectHigh();
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
chipSelectHigh();
|
chipSelectHigh();
|
||||||
return true;
|
return true;
|
||||||
FAIL:
|
|
||||||
chipSelectHigh();
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* Set the SPI clock rate.
|
* Set the SPI clock rate.
|
||||||
*
|
*
|
||||||
@@ -596,25 +588,22 @@ bool Sd2Card::setSckRate(uint8_t sckRateID) {
|
|||||||
spiRate_ = sckRateID;
|
spiRate_ = sckRateID;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// wait for card to go not busy
|
// wait for card to go not busy
|
||||||
bool Sd2Card::waitNotBusy(uint16_t timeoutMillis) {
|
bool Sd2Card::waitNotBusy(uint16_t timeoutMillis) {
|
||||||
uint16_t t0 = millis();
|
uint16_t t0 = millis();
|
||||||
while (spiRec() != 0XFF) {
|
while (spiRec() != 0XFF)
|
||||||
if (((uint16_t)millis() - t0) >= timeoutMillis) goto FAIL;
|
if (((uint16_t)millis() - t0) >= timeoutMillis) return false;
|
||||||
}
|
|
||||||
return true;
|
return true;
|
||||||
FAIL:
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* Writes a 512 byte block to an SD card.
|
* Writes a 512 byte block to an SD card.
|
||||||
*
|
*
|
||||||
* \param[in] blockNumber Logical block to be written.
|
* \param[in] blockNumber Logical block to be written.
|
||||||
* \param[in] src Pointer to the location of the data to be written.
|
* \param[in] src Pointer to the location of the data to be written.
|
||||||
* \return The value one, true, is returned for success and
|
* \return true for success, false for failure.
|
||||||
* the value zero, false, is returned for failure.
|
|
||||||
*/
|
*/
|
||||||
bool Sd2Card::writeBlock(uint32_t blockNumber, const uint8_t* src) {
|
bool Sd2Card::writeBlock(uint32_t blockNumber, const uint8_t* src) {
|
||||||
// use address if not SDHC card
|
// use address if not SDHC card
|
||||||
@@ -641,25 +630,24 @@ bool Sd2Card::writeBlock(uint32_t blockNumber, const uint8_t* src) {
|
|||||||
chipSelectHigh();
|
chipSelectHigh();
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Write one data block in a multiple block write sequence
|
/**
|
||||||
|
* Write one data block in a multiple block write sequence
|
||||||
* \param[in] src Pointer to the location of the data to be written.
|
* \param[in] src Pointer to the location of the data to be written.
|
||||||
* \return The value one, true, is returned for success and
|
* \return true for success, false for failure.
|
||||||
* the value zero, false, is returned for failure.
|
|
||||||
*/
|
*/
|
||||||
bool Sd2Card::writeData(const uint8_t* src) {
|
bool Sd2Card::writeData(const uint8_t* src) {
|
||||||
chipSelectLow();
|
chipSelectLow();
|
||||||
// wait for previous write to finish
|
// wait for previous write to finish
|
||||||
if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto FAIL;
|
if (!waitNotBusy(SD_WRITE_TIMEOUT) || !writeData(WRITE_MULTIPLE_TOKEN, src)) {
|
||||||
if (!writeData(WRITE_MULTIPLE_TOKEN, src)) goto FAIL;
|
|
||||||
chipSelectHigh();
|
|
||||||
return true;
|
|
||||||
FAIL:
|
|
||||||
error(SD_CARD_ERROR_WRITE_MULTIPLE);
|
error(SD_CARD_ERROR_WRITE_MULTIPLE);
|
||||||
chipSelectHigh();
|
chipSelectHigh();
|
||||||
return false;
|
return false;
|
||||||
|
}
|
||||||
|
chipSelectHigh();
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// send one block of data for write block or write multiple blocks
|
// send one block of data for write block or write multiple blocks
|
||||||
bool Sd2Card::writeData(uint8_t token, const uint8_t* src) {
|
bool Sd2Card::writeData(uint8_t token, const uint8_t* src) {
|
||||||
spiSendBlock(token, src);
|
spiSendBlock(token, src);
|
||||||
@@ -670,15 +658,14 @@ bool Sd2Card::writeData(uint8_t token, const uint8_t* src) {
|
|||||||
status_ = spiRec();
|
status_ = spiRec();
|
||||||
if ((status_ & DATA_RES_MASK) != DATA_RES_ACCEPTED) {
|
if ((status_ & DATA_RES_MASK) != DATA_RES_ACCEPTED) {
|
||||||
error(SD_CARD_ERROR_WRITE);
|
error(SD_CARD_ERROR_WRITE);
|
||||||
goto FAIL;
|
|
||||||
}
|
|
||||||
return true;
|
|
||||||
FAIL:
|
|
||||||
chipSelectHigh();
|
chipSelectHigh();
|
||||||
return false;
|
return false;
|
||||||
|
}
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Start a write multiple blocks sequence.
|
/**
|
||||||
|
* Start a write multiple blocks sequence.
|
||||||
*
|
*
|
||||||
* \param[in] blockNumber Address of first block in sequence.
|
* \param[in] blockNumber Address of first block in sequence.
|
||||||
* \param[in] eraseCount The number of blocks to be pre-erased.
|
* \param[in] eraseCount The number of blocks to be pre-erased.
|
||||||
@@ -686,8 +673,7 @@ bool Sd2Card::writeData(uint8_t token, const uint8_t* src) {
|
|||||||
* \note This function is used with writeData() and writeStop()
|
* \note This function is used with writeData() and writeStop()
|
||||||
* for optimized multiple block writes.
|
* for optimized multiple block writes.
|
||||||
*
|
*
|
||||||
* \return The value one, true, is returned for success and
|
* \return true for success, false for failure.
|
||||||
* the value zero, false, is returned for failure.
|
|
||||||
*/
|
*/
|
||||||
bool Sd2Card::writeStart(uint32_t blockNumber, uint32_t eraseCount) {
|
bool Sd2Card::writeStart(uint32_t blockNumber, uint32_t eraseCount) {
|
||||||
// send pre-erase count
|
// send pre-erase count
|
||||||
@@ -707,11 +693,11 @@ bool Sd2Card::writeStart(uint32_t blockNumber, uint32_t eraseCount) {
|
|||||||
chipSelectHigh();
|
chipSelectHigh();
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** End a write multiple blocks sequence.
|
/**
|
||||||
|
* End a write multiple blocks sequence.
|
||||||
*
|
*
|
||||||
* \return The value one, true, is returned for success and
|
* \return true for success, false for failure.
|
||||||
* the value zero, false, is returned for failure.
|
|
||||||
*/
|
*/
|
||||||
bool Sd2Card::writeStop() {
|
bool Sd2Card::writeStop() {
|
||||||
chipSelectLow();
|
chipSelectLow();
|
||||||
@@ -726,4 +712,4 @@ bool Sd2Card::writeStop() {
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif // SDSUPPORT
|
||||||
|
|||||||
213
Marlin/Sd2Card.h
213
Marlin/Sd2Card.h
@@ -20,165 +20,119 @@
|
|||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \file
|
||||||
|
* \brief Sd2Card class for V2 SD/SDHC cards
|
||||||
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Arduino Sd2Card Library
|
* Arduino Sd2Card Library
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Copyright (C) 2009 by William Greiman
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
|
#ifndef _SD2CARD_H_
|
||||||
|
#define _SD2CARD_H_
|
||||||
|
|
||||||
#include "Marlin.h"
|
|
||||||
#if ENABLED(SDSUPPORT)
|
|
||||||
|
|
||||||
#ifndef Sd2Card_h
|
|
||||||
#define Sd2Card_h
|
|
||||||
/**
|
|
||||||
* \file
|
|
||||||
* \brief Sd2Card class for V2 SD/SDHC cards
|
|
||||||
*/
|
|
||||||
#include "SdFatConfig.h"
|
#include "SdFatConfig.h"
|
||||||
#include "SdInfo.h"
|
#include "SdInfo.h"
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// SPI speed is F_CPU/2^(1 + index), 0 <= index <= 6
|
// SPI speed is F_CPU/2^(1 + index), 0 <= index <= 6
|
||||||
/** Set SCK to max rate of F_CPU/2. See Sd2Card::setSckRate(). */
|
uint8_t const SPI_FULL_SPEED = 0, // Set SCK to max rate of F_CPU/2. See Sd2Card::setSckRate().
|
||||||
uint8_t const SPI_FULL_SPEED = 0;
|
SPI_HALF_SPEED = 1, // Set SCK rate to F_CPU/4. See Sd2Card::setSckRate().
|
||||||
/** Set SCK rate to F_CPU/4. See Sd2Card::setSckRate(). */
|
SPI_QUARTER_SPEED = 2, // Set SCK rate to F_CPU/8. See Sd2Card::setSckRate().
|
||||||
uint8_t const SPI_HALF_SPEED = 1;
|
SPI_EIGHTH_SPEED = 3, // Set SCK rate to F_CPU/16. See Sd2Card::setSckRate().
|
||||||
/** Set SCK rate to F_CPU/8. See Sd2Card::setSckRate(). */
|
SPI_SIXTEENTH_SPEED = 4; // Set SCK rate to F_CPU/32. See Sd2Card::setSckRate().
|
||||||
uint8_t const SPI_QUARTER_SPEED = 2;
|
|
||||||
/** Set SCK rate to F_CPU/16. See Sd2Card::setSckRate(). */
|
uint16_t const SD_INIT_TIMEOUT = 2000, // init timeout ms
|
||||||
uint8_t const SPI_EIGHTH_SPEED = 3;
|
SD_ERASE_TIMEOUT = 10000, // erase timeout ms
|
||||||
/** Set SCK rate to F_CPU/32. See Sd2Card::setSckRate(). */
|
SD_READ_TIMEOUT = 300, // read timeout ms
|
||||||
uint8_t const SPI_SIXTEENTH_SPEED = 4;
|
SD_WRITE_TIMEOUT = 600; // write time out ms
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** init timeout ms */
|
|
||||||
uint16_t const SD_INIT_TIMEOUT = 2000;
|
|
||||||
/** erase timeout ms */
|
|
||||||
uint16_t const SD_ERASE_TIMEOUT = 10000;
|
|
||||||
/** read timeout ms */
|
|
||||||
uint16_t const SD_READ_TIMEOUT = 300;
|
|
||||||
/** write time out ms */
|
|
||||||
uint16_t const SD_WRITE_TIMEOUT = 600;
|
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// SD card errors
|
// SD card errors
|
||||||
/** timeout error for command CMD0 (initialize card in SPI mode) */
|
uint8_t const SD_CARD_ERROR_CMD0 = 0X1, // timeout error for command CMD0 (initialize card in SPI mode)
|
||||||
uint8_t const SD_CARD_ERROR_CMD0 = 0X1;
|
SD_CARD_ERROR_CMD8 = 0X2, // CMD8 was not accepted - not a valid SD card
|
||||||
/** CMD8 was not accepted - not a valid SD card*/
|
SD_CARD_ERROR_CMD12 = 0X3, // card returned an error response for CMD12 (write stop)
|
||||||
uint8_t const SD_CARD_ERROR_CMD8 = 0X2;
|
SD_CARD_ERROR_CMD17 = 0X4, // card returned an error response for CMD17 (read block)
|
||||||
/** card returned an error response for CMD12 (write stop) */
|
SD_CARD_ERROR_CMD18 = 0X5, // card returned an error response for CMD18 (read multiple block)
|
||||||
uint8_t const SD_CARD_ERROR_CMD12 = 0X3;
|
SD_CARD_ERROR_CMD24 = 0X6, // card returned an error response for CMD24 (write block)
|
||||||
/** card returned an error response for CMD17 (read block) */
|
SD_CARD_ERROR_CMD25 = 0X7, // WRITE_MULTIPLE_BLOCKS command failed
|
||||||
uint8_t const SD_CARD_ERROR_CMD17 = 0X4;
|
SD_CARD_ERROR_CMD58 = 0X8, // card returned an error response for CMD58 (read OCR)
|
||||||
/** card returned an error response for CMD18 (read multiple block) */
|
SD_CARD_ERROR_ACMD23 = 0X9, // SET_WR_BLK_ERASE_COUNT failed
|
||||||
uint8_t const SD_CARD_ERROR_CMD18 = 0X5;
|
SD_CARD_ERROR_ACMD41 = 0XA, // ACMD41 initialization process timeout
|
||||||
/** card returned an error response for CMD24 (write block) */
|
SD_CARD_ERROR_BAD_CSD = 0XB, // card returned a bad CSR version field
|
||||||
uint8_t const SD_CARD_ERROR_CMD24 = 0X6;
|
SD_CARD_ERROR_ERASE = 0XC, // erase block group command failed
|
||||||
/** WRITE_MULTIPLE_BLOCKS command failed */
|
SD_CARD_ERROR_ERASE_SINGLE_BLOCK = 0XD, // card not capable of single block erase
|
||||||
uint8_t const SD_CARD_ERROR_CMD25 = 0X7;
|
SD_CARD_ERROR_ERASE_TIMEOUT = 0XE, // Erase sequence timed out
|
||||||
/** card returned an error response for CMD58 (read OCR) */
|
SD_CARD_ERROR_READ = 0XF, // card returned an error token instead of read data
|
||||||
uint8_t const SD_CARD_ERROR_CMD58 = 0X8;
|
SD_CARD_ERROR_READ_REG = 0x10, // read CID or CSD failed
|
||||||
/** SET_WR_BLK_ERASE_COUNT failed */
|
SD_CARD_ERROR_READ_TIMEOUT = 0x11, // timeout while waiting for start of read data
|
||||||
uint8_t const SD_CARD_ERROR_ACMD23 = 0X9;
|
SD_CARD_ERROR_STOP_TRAN = 0x12, // card did not accept STOP_TRAN_TOKEN
|
||||||
/** ACMD41 initialization process timeout */
|
SD_CARD_ERROR_WRITE = 0x13, // card returned an error token as a response to a write operation
|
||||||
uint8_t const SD_CARD_ERROR_ACMD41 = 0XA;
|
SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0x14, // REMOVE - not used ... attempt to write protected block zero
|
||||||
/** card returned a bad CSR version field */
|
SD_CARD_ERROR_WRITE_MULTIPLE = 0x15, // card did not go ready for a multiple block write
|
||||||
uint8_t const SD_CARD_ERROR_BAD_CSD = 0XB;
|
SD_CARD_ERROR_WRITE_PROGRAMMING = 0x16, // card returned an error to a CMD13 status check after a write
|
||||||
/** erase block group command failed */
|
SD_CARD_ERROR_WRITE_TIMEOUT = 0x17, // timeout occurred during write programming
|
||||||
uint8_t const SD_CARD_ERROR_ERASE = 0XC;
|
SD_CARD_ERROR_SCK_RATE = 0x18, // incorrect rate selected
|
||||||
/** card not capable of single block erase */
|
SD_CARD_ERROR_INIT_NOT_CALLED = 0x19, // init() not called
|
||||||
uint8_t const SD_CARD_ERROR_ERASE_SINGLE_BLOCK = 0XD;
|
SD_CARD_ERROR_CRC = 0x20; // crc check error
|
||||||
/** Erase sequence timed out */
|
|
||||||
uint8_t const SD_CARD_ERROR_ERASE_TIMEOUT = 0XE;
|
|
||||||
/** card returned an error token instead of read data */
|
|
||||||
uint8_t const SD_CARD_ERROR_READ = 0XF;
|
|
||||||
/** read CID or CSD failed */
|
|
||||||
uint8_t const SD_CARD_ERROR_READ_REG = 0x10;
|
|
||||||
/** timeout while waiting for start of read data */
|
|
||||||
uint8_t const SD_CARD_ERROR_READ_TIMEOUT = 0x11;
|
|
||||||
/** card did not accept STOP_TRAN_TOKEN */
|
|
||||||
uint8_t const SD_CARD_ERROR_STOP_TRAN = 0x12;
|
|
||||||
/** card returned an error token as a response to a write operation */
|
|
||||||
uint8_t const SD_CARD_ERROR_WRITE = 0x13;
|
|
||||||
/** attempt to write protected block zero */
|
|
||||||
uint8_t const SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0x14; // REMOVE - not used
|
|
||||||
/** card did not go ready for a multiple block write */
|
|
||||||
uint8_t const SD_CARD_ERROR_WRITE_MULTIPLE = 0x15;
|
|
||||||
/** card returned an error to a CMD13 status check after a write */
|
|
||||||
uint8_t const SD_CARD_ERROR_WRITE_PROGRAMMING = 0x16;
|
|
||||||
/** timeout occurred during write programming */
|
|
||||||
uint8_t const SD_CARD_ERROR_WRITE_TIMEOUT = 0x17;
|
|
||||||
/** incorrect rate selected */
|
|
||||||
uint8_t const SD_CARD_ERROR_SCK_RATE = 0x18;
|
|
||||||
/** init() not called */
|
|
||||||
uint8_t const SD_CARD_ERROR_INIT_NOT_CALLED = 0x19;
|
|
||||||
/** crc check error */
|
|
||||||
uint8_t const SD_CARD_ERROR_CRC = 0x20;
|
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// card types
|
// card types
|
||||||
/** Standard capacity V1 SD card */
|
uint8_t const SD_CARD_TYPE_SD1 = 1, // Standard capacity V1 SD card
|
||||||
uint8_t const SD_CARD_TYPE_SD1 = 1;
|
SD_CARD_TYPE_SD2 = 2, // Standard capacity V2 SD card
|
||||||
/** Standard capacity V2 SD card */
|
SD_CARD_TYPE_SDHC = 3; // High Capacity SD card
|
||||||
uint8_t const SD_CARD_TYPE_SD2 = 2;
|
|
||||||
/** High Capacity SD card */
|
|
||||||
uint8_t const SD_CARD_TYPE_SDHC = 3;
|
|
||||||
/**
|
/**
|
||||||
* define SOFTWARE_SPI to use bit-bang SPI
|
* define SOFTWARE_SPI to use bit-bang SPI
|
||||||
*/
|
*/
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
#if MEGA_SOFT_SPI
|
#if MEGA_SOFT_SPI
|
||||||
#define SOFTWARE_SPI
|
#define SOFTWARE_SPI
|
||||||
#elif USE_SOFTWARE_SPI
|
#elif USE_SOFTWARE_SPI
|
||||||
#define SOFTWARE_SPI
|
#define SOFTWARE_SPI
|
||||||
#endif // MEGA_SOFT_SPI
|
#endif
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// SPI pin definitions - do not edit here - change in SdFatConfig.h
|
// SPI pin definitions - do not edit here - change in SdFatConfig.h
|
||||||
//
|
|
||||||
#if DISABLED(SOFTWARE_SPI)
|
#if DISABLED(SOFTWARE_SPI)
|
||||||
// hardware pin defs
|
// hardware pin defs
|
||||||
/** The default chip select pin for the SD card is SS. */
|
#define SD_CHIP_SELECT_PIN SS_PIN // The default chip select pin for the SD card is SS.
|
||||||
#define SD_CHIP_SELECT_PIN SS_PIN
|
|
||||||
// The following three pins must not be redefined for hardware SPI.
|
// The following three pins must not be redefined for hardware SPI.
|
||||||
/** SPI Master Out Slave In pin */
|
#define SPI_MOSI_PIN MOSI_PIN // SPI Master Out Slave In pin
|
||||||
#define SPI_MOSI_PIN MOSI_PIN
|
#define SPI_MISO_PIN MISO_PIN // SPI Master In Slave Out pin
|
||||||
/** SPI Master In Slave Out pin */
|
#define SPI_SCK_PIN SCK_PIN // SPI Clock pin
|
||||||
#define SPI_MISO_PIN MISO_PIN
|
|
||||||
/** SPI Clock pin */
|
|
||||||
#define SPI_SCK_PIN SCK_PIN
|
|
||||||
|
|
||||||
#else // SOFTWARE_SPI
|
#else // SOFTWARE_SPI
|
||||||
|
#define SD_CHIP_SELECT_PIN SOFT_SPI_CS_PIN // SPI chip select pin
|
||||||
/** SPI chip select pin */
|
#define SPI_MOSI_PIN SOFT_SPI_MOSI_PIN // SPI Master Out Slave In pin
|
||||||
#define SD_CHIP_SELECT_PIN SOFT_SPI_CS_PIN
|
#define SPI_MISO_PIN SOFT_SPI_MISO_PIN // SPI Master In Slave Out pin
|
||||||
/** SPI Master Out Slave In pin */
|
#define SPI_SCK_PIN SOFT_SPI_SCK_PIN // SPI Clock pin
|
||||||
#define SPI_MOSI_PIN SOFT_SPI_MOSI_PIN
|
|
||||||
/** SPI Master In Slave Out pin */
|
|
||||||
#define SPI_MISO_PIN SOFT_SPI_MISO_PIN
|
|
||||||
/** SPI Clock pin */
|
|
||||||
#define SPI_SCK_PIN SOFT_SPI_SCK_PIN
|
|
||||||
#endif // SOFTWARE_SPI
|
#endif // SOFTWARE_SPI
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* \class Sd2Card
|
* \class Sd2Card
|
||||||
* \brief Raw access to SD and SDHC flash memory cards.
|
* \brief Raw access to SD and SDHC flash memory cards.
|
||||||
*/
|
*/
|
||||||
class Sd2Card {
|
class Sd2Card {
|
||||||
public:
|
public:
|
||||||
/** Construct an instance of Sd2Card. */
|
|
||||||
Sd2Card() : errorCode_(SD_CARD_ERROR_INIT_NOT_CALLED), type_(0) {}
|
Sd2Card() : errorCode_(SD_CARD_ERROR_INIT_NOT_CALLED), type_(0) {}
|
||||||
|
|
||||||
uint32_t cardSize();
|
uint32_t cardSize();
|
||||||
bool erase(uint32_t firstBlock, uint32_t lastBlock);
|
bool erase(uint32_t firstBlock, uint32_t lastBlock);
|
||||||
bool eraseSingleBlockEnable();
|
bool eraseSingleBlockEnable();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Set SD error code.
|
* Set SD error code.
|
||||||
* \param[in] code value for error code.
|
* \param[in] code value for error code.
|
||||||
*/
|
*/
|
||||||
void error(uint8_t code) {errorCode_ = code;}
|
void error(uint8_t code) {errorCode_ = code;}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* \return error code for last error. See Sd2Card.h for a list of error codes.
|
* \return error code for last error. See Sd2Card.h for a list of error codes.
|
||||||
*/
|
*/
|
||||||
int errorCode() const {return errorCode_;}
|
int errorCode() const {return errorCode_;}
|
||||||
|
|
||||||
/** \return error data for last error. */
|
/** \return error data for last error. */
|
||||||
int errorData() const {return status_;}
|
int errorData() const {return status_;}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Initialize an SD flash memory card with default clock rate and chip
|
* Initialize an SD flash memory card with default clock rate and chip
|
||||||
* select pin. See sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin).
|
* select pin. See sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin).
|
||||||
@@ -188,6 +142,7 @@ class Sd2Card {
|
|||||||
bool init(uint8_t sckRateID = SPI_FULL_SPEED,
|
bool init(uint8_t sckRateID = SPI_FULL_SPEED,
|
||||||
uint8_t chipSelectPin = SD_CHIP_SELECT_PIN);
|
uint8_t chipSelectPin = SD_CHIP_SELECT_PIN);
|
||||||
bool readBlock(uint32_t block, uint8_t* dst);
|
bool readBlock(uint32_t block, uint8_t* dst);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Read a card's CID register. The CID contains card identification
|
* Read a card's CID register. The CID contains card identification
|
||||||
* information such as Manufacturer ID, Product name, Product serial
|
* information such as Manufacturer ID, Product name, Product serial
|
||||||
@@ -197,9 +152,8 @@ class Sd2Card {
|
|||||||
*
|
*
|
||||||
* \return true for success or false for failure.
|
* \return true for success or false for failure.
|
||||||
*/
|
*/
|
||||||
bool readCID(cid_t* cid) {
|
bool readCID(cid_t* cid) { return readRegister(CMD10, cid); }
|
||||||
return readRegister(CMD10, cid);
|
|
||||||
}
|
|
||||||
/**
|
/**
|
||||||
* Read a card's CSD register. The CSD contains Card-Specific Data that
|
* Read a card's CSD register. The CSD contains Card-Specific Data that
|
||||||
* provides information regarding access to the card's contents.
|
* provides information regarding access to the card's contents.
|
||||||
@@ -208,14 +162,14 @@ class Sd2Card {
|
|||||||
*
|
*
|
||||||
* \return true for success or false for failure.
|
* \return true for success or false for failure.
|
||||||
*/
|
*/
|
||||||
bool readCSD(csd_t* csd) {
|
bool readCSD(csd_t* csd) { return readRegister(CMD9, csd); }
|
||||||
return readRegister(CMD9, csd);
|
|
||||||
}
|
|
||||||
bool readData(uint8_t* dst);
|
bool readData(uint8_t* dst);
|
||||||
bool readStart(uint32_t blockNumber);
|
bool readStart(uint32_t blockNumber);
|
||||||
bool readStop();
|
bool readStop();
|
||||||
bool setSckRate(uint8_t sckRateID);
|
bool setSckRate(uint8_t sckRateID);
|
||||||
/** Return the card type: SD V1, SD V2 or SDHC
|
/**
|
||||||
|
* Return the card type: SD V1, SD V2 or SDHC
|
||||||
* \return 0 - SD V1, 1 - SD V2, or 3 - SDHC.
|
* \return 0 - SD V1, 1 - SD V2, or 3 - SDHC.
|
||||||
*/
|
*/
|
||||||
int type() const {return type_;}
|
int type() const {return type_;}
|
||||||
@@ -223,13 +177,14 @@ class Sd2Card {
|
|||||||
bool writeData(const uint8_t* src);
|
bool writeData(const uint8_t* src);
|
||||||
bool writeStart(uint32_t blockNumber, uint32_t eraseCount);
|
bool writeStart(uint32_t blockNumber, uint32_t eraseCount);
|
||||||
bool writeStop();
|
bool writeStop();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
//----------------------------------------------------------------------------
|
uint8_t chipSelectPin_,
|
||||||
uint8_t chipSelectPin_;
|
errorCode_,
|
||||||
uint8_t errorCode_;
|
spiRate_,
|
||||||
uint8_t spiRate_;
|
status_,
|
||||||
uint8_t status_;
|
type_;
|
||||||
uint8_t type_;
|
|
||||||
// private functions
|
// private functions
|
||||||
uint8_t cardAcmd(uint8_t cmd, uint32_t arg) {
|
uint8_t cardAcmd(uint8_t cmd, uint32_t arg) {
|
||||||
cardCommand(CMD55, 0);
|
cardCommand(CMD55, 0);
|
||||||
@@ -241,11 +196,9 @@ class Sd2Card {
|
|||||||
bool readRegister(uint8_t cmd, void* buf);
|
bool readRegister(uint8_t cmd, void* buf);
|
||||||
void chipSelectHigh();
|
void chipSelectHigh();
|
||||||
void chipSelectLow();
|
void chipSelectLow();
|
||||||
void type(uint8_t value) {type_ = value;}
|
void type(uint8_t value) { type_ = value; }
|
||||||
bool waitNotBusy(uint16_t timeoutMillis);
|
bool waitNotBusy(uint16_t timeoutMillis);
|
||||||
bool writeData(uint8_t token, const uint8_t* src);
|
bool writeData(uint8_t token, const uint8_t* src);
|
||||||
};
|
};
|
||||||
#endif // Sd2Card_h
|
|
||||||
|
|
||||||
|
#endif // _SD2CARD_H_
|
||||||
#endif
|
|
||||||
|
|||||||
File diff suppressed because it is too large
Load Diff
@@ -20,208 +20,196 @@
|
|||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \file
|
||||||
|
* \brief SdBaseFile class
|
||||||
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Arduino SdFat Library
|
* Arduino SdFat Library
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Copyright (C) 2009 by William Greiman
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#ifndef _SDBASEFILE_H_
|
||||||
#if ENABLED(SDSUPPORT)
|
#define _SDBASEFILE_H_
|
||||||
|
|
||||||
#ifndef SdBaseFile_h
|
|
||||||
#define SdBaseFile_h
|
|
||||||
/**
|
|
||||||
* \file
|
|
||||||
* \brief SdBaseFile class
|
|
||||||
*/
|
|
||||||
#include "Marlin.h"
|
|
||||||
#include "SdFatConfig.h"
|
#include "SdFatConfig.h"
|
||||||
#include "SdVolume.h"
|
#include "SdVolume.h"
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* \struct filepos_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 filepos_t {
|
struct filepos_t {
|
||||||
/** stream position */
|
uint32_t position; // stream byte position
|
||||||
uint32_t position;
|
uint32_t cluster; // cluster of position
|
||||||
/** cluster for position */
|
|
||||||
uint32_t cluster;
|
|
||||||
filepos_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()
|
||||||
/** open() oflag for reading */
|
uint8_t const O_READ = 0x01, // open() oflag for reading
|
||||||
uint8_t const O_READ = 0x01;
|
O_RDONLY = O_READ, // open() oflag - same as O_IN
|
||||||
/** open() oflag - same as O_IN */
|
O_WRITE = 0x02, // open() oflag for write
|
||||||
uint8_t const O_RDONLY = O_READ;
|
O_WRONLY = O_WRITE, // open() oflag - same as O_WRITE
|
||||||
/** open() oflag for write */
|
O_RDWR = (O_READ | O_WRITE), // open() oflag for reading and writing
|
||||||
uint8_t const O_WRITE = 0x02;
|
O_ACCMODE = (O_READ | O_WRITE), // open() oflag mask for access modes
|
||||||
/** open() oflag - same as O_WRITE */
|
O_APPEND = 0x04, // The file offset shall be set to the end of the file prior to each write.
|
||||||
uint8_t const O_WRONLY = O_WRITE;
|
O_SYNC = 0x08, // Synchronous writes - call sync() after each write
|
||||||
/** open() oflag for reading and writing */
|
O_TRUNC = 0x10, // Truncate the file to zero length
|
||||||
uint8_t const O_RDWR = (O_READ | O_WRITE);
|
O_AT_END = 0x20, // Set the initial position at the end of the file
|
||||||
/** open() oflag mask for access modes */
|
O_CREAT = 0x40, // Create the file if nonexistent
|
||||||
uint8_t const O_ACCMODE = (O_READ | O_WRITE);
|
O_EXCL = 0x80; // If O_CREAT and O_EXCL are set, open() shall fail if the file exists
|
||||||
/** The file offset shall be set to the end of the file prior to each write. */
|
|
||||||
uint8_t const O_APPEND = 0x04;
|
|
||||||
/** synchronous writes - call sync() after each write */
|
|
||||||
uint8_t const O_SYNC = 0x08;
|
|
||||||
/** truncate the file to zero length */
|
|
||||||
uint8_t const O_TRUNC = 0x10;
|
|
||||||
/** set the initial position at the end of the file */
|
|
||||||
uint8_t const O_AT_END = 0x20;
|
|
||||||
/** create the file if nonexistent */
|
|
||||||
uint8_t const O_CREAT = 0x40;
|
|
||||||
/** If O_CREAT and O_EXCL are set, open() shall fail if the file exists */
|
|
||||||
uint8_t const O_EXCL = 0x80;
|
|
||||||
|
|
||||||
// SdBaseFile class static and const definitions
|
// SdBaseFile class static and const definitions
|
||||||
|
|
||||||
// flags for ls()
|
// flags for ls()
|
||||||
/** ls() flag to print modify date */
|
uint8_t const LS_DATE = 1, // ls() flag to print modify date
|
||||||
uint8_t const LS_DATE = 1;
|
LS_SIZE = 2, // ls() flag to print file size
|
||||||
/** ls() flag to print file size */
|
LS_R = 4; // ls() flag for recursive list of subdirectories
|
||||||
uint8_t const LS_SIZE = 2;
|
|
||||||
/** ls() flag for recursive list of subdirectories */
|
|
||||||
uint8_t const LS_R = 4;
|
|
||||||
|
|
||||||
|
|
||||||
// flags for timestamp
|
// flags for timestamp
|
||||||
/** set the file's last access date */
|
uint8_t const T_ACCESS = 1, // Set the file's last access date
|
||||||
uint8_t const T_ACCESS = 1;
|
T_CREATE = 2, // Set the file's creation date and time
|
||||||
/** set the file's creation date and time */
|
T_WRITE = 4; // Set the file's write date and time
|
||||||
uint8_t const T_CREATE = 2;
|
|
||||||
/** Set the file's write date and time */
|
|
||||||
uint8_t const T_WRITE = 4;
|
|
||||||
// values for type_
|
|
||||||
/** This file has not been opened. */
|
|
||||||
uint8_t const FAT_FILE_TYPE_CLOSED = 0;
|
|
||||||
/** A normal file */
|
|
||||||
uint8_t const FAT_FILE_TYPE_NORMAL = 1;
|
|
||||||
/** A FAT12 or FAT16 root directory */
|
|
||||||
uint8_t const FAT_FILE_TYPE_ROOT_FIXED = 2;
|
|
||||||
/** A FAT32 root directory */
|
|
||||||
uint8_t const FAT_FILE_TYPE_ROOT32 = 3;
|
|
||||||
/** A subdirectory file*/
|
|
||||||
uint8_t const FAT_FILE_TYPE_SUBDIR = 4;
|
|
||||||
/** Test value for directory type */
|
|
||||||
uint8_t const FAT_FILE_TYPE_MIN_DIR = FAT_FILE_TYPE_ROOT_FIXED;
|
|
||||||
|
|
||||||
/** date field for FAT directory entry
|
// values for type_
|
||||||
|
uint8_t const FAT_FILE_TYPE_CLOSED = 0, // This file has not been opened.
|
||||||
|
FAT_FILE_TYPE_NORMAL = 1, // A normal file
|
||||||
|
FAT_FILE_TYPE_ROOT_FIXED = 2, // A FAT12 or FAT16 root directory
|
||||||
|
FAT_FILE_TYPE_ROOT32 = 3, // A FAT32 root directory
|
||||||
|
FAT_FILE_TYPE_SUBDIR = 4, // A subdirectory file
|
||||||
|
FAT_FILE_TYPE_MIN_DIR = FAT_FILE_TYPE_ROOT_FIXED; // Test value for directory type
|
||||||
|
|
||||||
|
/**
|
||||||
|
* date field for FAT directory entry
|
||||||
* \param[in] year [1980,2107]
|
* \param[in] year [1980,2107]
|
||||||
* \param[in] month [1,12]
|
* \param[in] month [1,12]
|
||||||
* \param[in] day [1,31]
|
* \param[in] day [1,31]
|
||||||
*
|
*
|
||||||
* \return Packed date for dir_t entry.
|
* \return Packed date for dir_t entry.
|
||||||
*/
|
*/
|
||||||
static inline uint16_t FAT_DATE(uint16_t year, uint8_t month, uint8_t day) {
|
static inline uint16_t FAT_DATE(uint16_t year, uint8_t month, uint8_t day) { return (year - 1980) << 9 | month << 5 | day; }
|
||||||
return (year - 1980) << 9 | month << 5 | day;
|
|
||||||
}
|
/**
|
||||||
/** year part of FAT directory date field
|
* year part of FAT directory date field
|
||||||
* \param[in] fatDate Date in packed dir format.
|
* \param[in] fatDate Date in packed dir format.
|
||||||
*
|
*
|
||||||
* \return Extracted year [1980,2107]
|
* \return Extracted year [1980,2107]
|
||||||
*/
|
*/
|
||||||
static inline uint16_t FAT_YEAR(uint16_t fatDate) {
|
static inline uint16_t FAT_YEAR(uint16_t fatDate) { return 1980 + (fatDate >> 9); }
|
||||||
return 1980 + (fatDate >> 9);
|
|
||||||
}
|
/**
|
||||||
/** month part of FAT directory date field
|
* month part of FAT directory date field
|
||||||
* \param[in] fatDate Date in packed dir format.
|
* \param[in] fatDate Date in packed dir format.
|
||||||
*
|
*
|
||||||
* \return Extracted month [1,12]
|
* \return Extracted month [1,12]
|
||||||
*/
|
*/
|
||||||
static inline uint8_t FAT_MONTH(uint16_t fatDate) {
|
static inline uint8_t FAT_MONTH(uint16_t fatDate) { return (fatDate >> 5) & 0XF; }
|
||||||
return (fatDate >> 5) & 0XF;
|
|
||||||
}
|
/**
|
||||||
/** day part of FAT directory date field
|
* day part of FAT directory date field
|
||||||
* \param[in] fatDate Date in packed dir format.
|
* \param[in] fatDate Date in packed dir format.
|
||||||
*
|
*
|
||||||
* \return Extracted day [1,31]
|
* \return Extracted day [1,31]
|
||||||
*/
|
*/
|
||||||
static inline uint8_t FAT_DAY(uint16_t fatDate) {
|
static inline uint8_t FAT_DAY(uint16_t fatDate) { return fatDate & 0x1F; }
|
||||||
return fatDate & 0x1F;
|
|
||||||
}
|
/**
|
||||||
/** time field for FAT directory entry
|
* time field for FAT directory entry
|
||||||
* \param[in] hour [0,23]
|
* \param[in] hour [0,23]
|
||||||
* \param[in] minute [0,59]
|
* \param[in] minute [0,59]
|
||||||
* \param[in] second [0,59]
|
* \param[in] second [0,59]
|
||||||
*
|
*
|
||||||
* \return Packed time for dir_t entry.
|
* \return Packed time for dir_t entry.
|
||||||
*/
|
*/
|
||||||
static inline uint16_t FAT_TIME(uint8_t hour, uint8_t minute, uint8_t second) {
|
static inline uint16_t FAT_TIME(uint8_t hour, uint8_t minute, uint8_t second) { return hour << 11 | minute << 5 | second >> 1; }
|
||||||
return hour << 11 | minute << 5 | second >> 1;
|
|
||||||
}
|
/**
|
||||||
/** hour part of FAT directory time field
|
* hour part of FAT directory time field
|
||||||
* \param[in] fatTime Time in packed dir format.
|
* \param[in] fatTime Time in packed dir format.
|
||||||
*
|
*
|
||||||
* \return Extracted hour [0,23]
|
* \return Extracted hour [0,23]
|
||||||
*/
|
*/
|
||||||
static inline uint8_t FAT_HOUR(uint16_t fatTime) {
|
static inline uint8_t FAT_HOUR(uint16_t fatTime) { return fatTime >> 11; }
|
||||||
return fatTime >> 11;
|
|
||||||
}
|
/**
|
||||||
/** minute part of FAT directory time field
|
* minute part of FAT directory time field
|
||||||
* \param[in] fatTime Time in packed dir format.
|
* \param[in] fatTime Time in packed dir format.
|
||||||
*
|
*
|
||||||
* \return Extracted minute [0,59]
|
* \return Extracted minute [0,59]
|
||||||
*/
|
*/
|
||||||
static inline uint8_t FAT_MINUTE(uint16_t fatTime) {
|
static inline uint8_t FAT_MINUTE(uint16_t fatTime) { return (fatTime >> 5) & 0x3F; }
|
||||||
return (fatTime >> 5) & 0x3F;
|
|
||||||
}
|
/**
|
||||||
/** second part of FAT directory time field
|
* second part of FAT directory time field
|
||||||
* Note second/2 is stored in packed time.
|
* Note second/2 is stored in packed time.
|
||||||
*
|
*
|
||||||
* \param[in] fatTime Time in packed dir format.
|
* \param[in] fatTime Time in packed dir format.
|
||||||
*
|
*
|
||||||
* \return Extracted second [0,58]
|
* \return Extracted second [0,58]
|
||||||
*/
|
*/
|
||||||
static inline uint8_t FAT_SECOND(uint16_t fatTime) {
|
static inline uint8_t FAT_SECOND(uint16_t fatTime) { return 2 * (fatTime & 0x1F); }
|
||||||
return 2 * (fatTime & 0x1F);
|
|
||||||
}
|
// Default date for file timestamps is 1 Jan 2000
|
||||||
/** Default date for file timestamps is 1 Jan 2000 */
|
|
||||||
uint16_t const FAT_DEFAULT_DATE = ((2000 - 1980) << 9) | (1 << 5) | 1;
|
uint16_t const FAT_DEFAULT_DATE = ((2000 - 1980) << 9) | (1 << 5) | 1;
|
||||||
/** Default time for file timestamp is 1 am */
|
// Default time for file timestamp is 1 am
|
||||||
uint16_t const FAT_DEFAULT_TIME = (1 << 11);
|
uint16_t const FAT_DEFAULT_TIME = (1 << 11);
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* \class SdBaseFile
|
* \class SdBaseFile
|
||||||
* \brief Base class for SdFile with Print and C++ streams.
|
* \brief Base class for SdFile with Print and C++ streams.
|
||||||
*/
|
*/
|
||||||
class SdBaseFile {
|
class SdBaseFile {
|
||||||
public:
|
public:
|
||||||
/** Create an instance. */
|
|
||||||
SdBaseFile() : writeError(false), type_(FAT_FILE_TYPE_CLOSED) {}
|
SdBaseFile() : writeError(false), type_(FAT_FILE_TYPE_CLOSED) {}
|
||||||
SdBaseFile(const char* path, uint8_t oflag);
|
SdBaseFile(const char* path, uint8_t oflag);
|
||||||
~SdBaseFile() {if (isOpen()) close();}
|
~SdBaseFile() { if (isOpen()) close(); }
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* writeError is set to true if an error occurs during a write().
|
* writeError is set to true if an error occurs during a write().
|
||||||
* Set writeError to false before calling print() and/or write() and check
|
* Set writeError to false before calling print() and/or write() and check
|
||||||
* for true after calls to print() and/or write().
|
* for true after calls to print() and/or write().
|
||||||
*/
|
*/
|
||||||
bool writeError;
|
bool writeError;
|
||||||
//----------------------------------------------------------------------------
|
|
||||||
// helpers for stream classes
|
// helpers for stream classes
|
||||||
/** get position for streams
|
|
||||||
|
/**
|
||||||
|
* get position for streams
|
||||||
* \param[out] pos struct to receive position
|
* \param[out] pos struct to receive position
|
||||||
*/
|
*/
|
||||||
void getpos(filepos_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(filepos_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);
|
||||||
bool createContiguous(SdBaseFile* dirFile,
|
bool createContiguous(SdBaseFile* dirFile,
|
||||||
const char* path, uint32_t size);
|
const char* path, uint32_t size);
|
||||||
/** \return The current cluster number for a file or directory. */
|
/**
|
||||||
uint32_t curCluster() const {return curCluster_;}
|
* \return The current cluster number for a file or directory.
|
||||||
/** \return The current position for a file or directory. */
|
*/
|
||||||
uint32_t curPosition() const {return curPosition_;}
|
uint32_t curCluster() const { return curCluster_; }
|
||||||
/** \return Current working directory */
|
|
||||||
static SdBaseFile* cwd() {return cwd_;}
|
/**
|
||||||
/** Set the date/time callback function
|
* \return The current position for a file or directory.
|
||||||
|
*/
|
||||||
|
uint32_t curPosition() const { return curPosition_; }
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \return Current working directory
|
||||||
|
*/
|
||||||
|
static SdBaseFile* cwd() { return cwd_; }
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set the date/time callback function
|
||||||
*
|
*
|
||||||
* \param[in] dateTime The user's call back function. The callback
|
* \param[in] dateTime The user's call back function. The callback
|
||||||
* function is of the form:
|
* function is of the form:
|
||||||
@@ -252,35 +240,55 @@ class SdBaseFile {
|
|||||||
void (*dateTime)(uint16_t* date, uint16_t* time)) {
|
void (*dateTime)(uint16_t* date, uint16_t* time)) {
|
||||||
dateTime_ = dateTime;
|
dateTime_ = dateTime;
|
||||||
}
|
}
|
||||||
/** Cancel the date/time callback function. */
|
|
||||||
static void dateTimeCallbackCancel() {dateTime_ = 0;}
|
/**
|
||||||
|
* Cancel the date/time callback function.
|
||||||
|
*/
|
||||||
|
static void dateTimeCallbackCancel() { dateTime_ = 0; }
|
||||||
bool dirEntry(dir_t* dir);
|
bool dirEntry(dir_t* dir);
|
||||||
static void dirName(const dir_t& dir, char* name);
|
static void dirName(const dir_t& dir, char* name);
|
||||||
bool exists(const char* name);
|
bool exists(const char* name);
|
||||||
int16_t fgets(char* str, int16_t num, char* delim = 0);
|
int16_t fgets(char* str, int16_t num, char* delim = 0);
|
||||||
/** \return The total number of bytes in a file or directory. */
|
|
||||||
uint32_t fileSize() const {return fileSize_;}
|
/**
|
||||||
/** \return The first cluster number for a file or directory. */
|
* \return The total number of bytes in a file or directory.
|
||||||
uint32_t firstCluster() const {return firstCluster_;}
|
*/
|
||||||
bool getFilename(char* name);
|
uint32_t fileSize() const { return fileSize_; }
|
||||||
/** \return True if this is a directory else false. */
|
|
||||||
bool isDir() const {return type_ >= FAT_FILE_TYPE_MIN_DIR;}
|
/**
|
||||||
/** \return True if this is a normal file else false. */
|
* \return The first cluster number for a file or directory.
|
||||||
bool isFile() const {return type_ == FAT_FILE_TYPE_NORMAL;}
|
*/
|
||||||
/** \return True if this is an open file/directory else false. */
|
uint32_t firstCluster() const { return firstCluster_; }
|
||||||
bool isOpen() const {return type_ != FAT_FILE_TYPE_CLOSED;}
|
|
||||||
/** \return True if this is a subdirectory else false. */
|
/**
|
||||||
bool isSubDir() const {return type_ == FAT_FILE_TYPE_SUBDIR;}
|
* \return True if this is a directory else false.
|
||||||
/** \return True if this is the root directory. */
|
*/
|
||||||
bool isRoot() const {
|
bool isDir() const { return type_ >= FAT_FILE_TYPE_MIN_DIR; }
|
||||||
return type_ == FAT_FILE_TYPE_ROOT_FIXED || type_ == FAT_FILE_TYPE_ROOT32;
|
|
||||||
}
|
/**
|
||||||
|
* \return True if this is a normal file else false.
|
||||||
|
*/
|
||||||
|
bool isFile() const { return type_ == FAT_FILE_TYPE_NORMAL; }
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \return True if this is an open file/directory else false.
|
||||||
|
*/
|
||||||
|
bool isOpen() const { return type_ != FAT_FILE_TYPE_CLOSED; }
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \return True if this is a subdirectory else false.
|
||||||
|
*/
|
||||||
|
bool isSubDir() const { return type_ == FAT_FILE_TYPE_SUBDIR; }
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \return True if this is the root directory.
|
||||||
|
*/
|
||||||
|
bool isRoot() const { return type_ == FAT_FILE_TYPE_ROOT_FIXED || type_ == FAT_FILE_TYPE_ROOT32; }
|
||||||
|
|
||||||
|
bool getFilename(char * const name);
|
||||||
void ls(uint8_t flags = 0, uint8_t indent = 0);
|
void ls(uint8_t flags = 0, uint8_t indent = 0);
|
||||||
|
|
||||||
bool mkdir(SdBaseFile* dir, const char* path, bool pFlag = true);
|
bool mkdir(SdBaseFile* dir, const char* path, bool pFlag = true);
|
||||||
// alias for backward compactability
|
|
||||||
bool makeDir(SdBaseFile* dir, const char* path) {
|
|
||||||
return mkdir(dir, path, false);
|
|
||||||
}
|
|
||||||
bool open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag);
|
bool open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag);
|
||||||
bool open(SdBaseFile* dirFile, const char* path, uint8_t oflag);
|
bool open(SdBaseFile* dirFile, const char* path, uint8_t oflag);
|
||||||
bool open(const char* path, uint8_t oflag = O_READ);
|
bool open(const char* path, uint8_t oflag = O_READ);
|
||||||
@@ -295,53 +303,58 @@ class SdBaseFile {
|
|||||||
int8_t readDir(dir_t* dir, char* longFilename);
|
int8_t readDir(dir_t* dir, char* longFilename);
|
||||||
static bool remove(SdBaseFile* dirFile, const char* path);
|
static bool remove(SdBaseFile* dirFile, const char* path);
|
||||||
bool remove();
|
bool remove();
|
||||||
/** Set the file's current position to zero. */
|
|
||||||
void rewind() {seekSet(0);}
|
/**
|
||||||
|
* Set the file's current position to zero.
|
||||||
|
*/
|
||||||
|
void rewind() { seekSet(0); }
|
||||||
bool rename(SdBaseFile* dirFile, const char* newPath);
|
bool rename(SdBaseFile* dirFile, const char* newPath);
|
||||||
bool rmdir();
|
bool rmdir();
|
||||||
// for backward compatibility
|
|
||||||
bool rmDir() {return rmdir();}
|
|
||||||
bool rmRfStar();
|
bool rmRfStar();
|
||||||
/** Set the files position to current position + \a pos. See seekSet().
|
|
||||||
|
/**
|
||||||
|
* Set the files position to current position + \a pos. See seekSet().
|
||||||
* \param[in] offset The new position in bytes from the current position.
|
* \param[in] offset The new position in bytes from the current position.
|
||||||
* \return true for success or false for failure.
|
* \return true for success or false for failure.
|
||||||
*/
|
*/
|
||||||
bool seekCur(int32_t offset) {
|
bool seekCur(const int32_t offset) { return seekSet(curPosition_ + offset); }
|
||||||
return seekSet(curPosition_ + offset);
|
|
||||||
}
|
/**
|
||||||
/** Set the files position to end-of-file + \a offset. See seekSet().
|
* Set the files position to end-of-file + \a offset. See seekSet().
|
||||||
* \param[in] offset The new position in bytes from end-of-file.
|
* \param[in] offset The new position in bytes from end-of-file.
|
||||||
* \return true for success or false for failure.
|
* \return true for success or false for failure.
|
||||||
*/
|
*/
|
||||||
bool seekEnd(int32_t offset = 0) {return seekSet(fileSize_ + offset);}
|
bool seekEnd(const int32_t offset = 0) { return seekSet(fileSize_ + offset); }
|
||||||
bool seekSet(uint32_t pos);
|
bool seekSet(const uint32_t pos);
|
||||||
bool sync();
|
bool sync();
|
||||||
bool timestamp(SdBaseFile* file);
|
bool timestamp(SdBaseFile* file);
|
||||||
bool timestamp(uint8_t flag, uint16_t year, uint8_t month, uint8_t day,
|
bool timestamp(uint8_t flag, uint16_t year, uint8_t month, uint8_t day,
|
||||||
uint8_t hour, uint8_t minute, uint8_t second);
|
uint8_t hour, uint8_t minute, uint8_t second);
|
||||||
/** Type of file. You should use isFile() or isDir() instead of type()
|
|
||||||
* if possible.
|
/**
|
||||||
|
* Type of file. Use isFile() or isDir() instead of type() if possible.
|
||||||
*
|
*
|
||||||
* \return The file or directory type.
|
* \return The file or directory type.
|
||||||
*/
|
*/
|
||||||
uint8_t type() const {return type_;}
|
uint8_t type() const { return type_; }
|
||||||
bool truncate(uint32_t size);
|
bool truncate(uint32_t size);
|
||||||
/** \return SdVolume that contains this file. */
|
|
||||||
SdVolume* volume() const {return vol_;}
|
/**
|
||||||
|
* \return SdVolume that contains this file.
|
||||||
|
*/
|
||||||
|
SdVolume* volume() const { return vol_; }
|
||||||
int16_t write(const void* buf, uint16_t nbyte);
|
int16_t write(const void* buf, uint16_t nbyte);
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
private:
|
private:
|
||||||
// allow SdFat to set cwd_
|
friend class SdFat; // allow SdFat to set cwd_
|
||||||
friend class SdFat;
|
static SdBaseFile* cwd_; // global pointer to cwd dir
|
||||||
// global pointer to cwd dir
|
|
||||||
static SdBaseFile* cwd_;
|
|
||||||
// data time callback function
|
// data time callback function
|
||||||
static void (*dateTime_)(uint16_t* date, uint16_t* time);
|
static void (*dateTime_)(uint16_t* date, uint16_t* time);
|
||||||
|
|
||||||
// bits defined in flags_
|
// bits defined in flags_
|
||||||
// should be 0x0F
|
static uint8_t const F_OFLAG = (O_ACCMODE | O_APPEND | O_SYNC), // should be 0x0F
|
||||||
static uint8_t const F_OFLAG = (O_ACCMODE | O_APPEND | O_SYNC);
|
F_FILE_DIR_DIRTY = 0x80; // sync of directory entry required
|
||||||
// sync of directory entry required
|
|
||||||
static uint8_t const F_FILE_DIR_DIRTY = 0x80;
|
|
||||||
|
|
||||||
// private data
|
// private data
|
||||||
uint8_t flags_; // See above for definition of flags_ bits
|
uint8_t flags_; // See above for definition of flags_ bits
|
||||||
@@ -355,8 +368,11 @@ class SdBaseFile {
|
|||||||
uint32_t firstCluster_; // first cluster of file
|
uint32_t firstCluster_; // first cluster of file
|
||||||
SdVolume* vol_; // volume where file is located
|
SdVolume* vol_; // volume where file is located
|
||||||
|
|
||||||
/** experimental don't use */
|
/**
|
||||||
bool openParent(SdBaseFile* dir);
|
* EXPERIMENTAL - Don't use!
|
||||||
|
*/
|
||||||
|
//bool openParent(SdBaseFile* dir);
|
||||||
|
|
||||||
// private functions
|
// private functions
|
||||||
bool addCluster();
|
bool addCluster();
|
||||||
bool addDirCluster();
|
bool addDirCluster();
|
||||||
@@ -367,61 +383,48 @@ class SdBaseFile {
|
|||||||
bool open(SdBaseFile* dirFile, const uint8_t dname[11], uint8_t oflag);
|
bool open(SdBaseFile* dirFile, const uint8_t dname[11], uint8_t oflag);
|
||||||
bool openCachedEntry(uint8_t cacheIndex, uint8_t oflags);
|
bool openCachedEntry(uint8_t cacheIndex, uint8_t oflags);
|
||||||
dir_t* readDirCache();
|
dir_t* readDirCache();
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// to be deleted
|
// Deprecated functions
|
||||||
static void printDirName(const dir_t& dir,
|
#if ALLOW_DEPRECATED_FUNCTIONS
|
||||||
uint8_t width, bool printSlash);
|
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// Deprecated functions - suppress cpplint warnings with NOLINT comment
|
|
||||||
#if ALLOW_DEPRECATED_FUNCTIONS && !defined(DOXYGEN)
|
|
||||||
public:
|
public:
|
||||||
/** \deprecated Use:
|
|
||||||
|
/**
|
||||||
|
* \deprecated Use:
|
||||||
* bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
|
* bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
|
||||||
* \param[out] bgnBlock the first block address for the file.
|
* \param[out] bgnBlock the first block address for the file.
|
||||||
* \param[out] endBlock the last block address for the file.
|
* \param[out] endBlock the last block address for the file.
|
||||||
* \return true for success or false for failure.
|
* \return true for success or false for failure.
|
||||||
*/
|
*/
|
||||||
bool contiguousRange(uint32_t& bgnBlock, uint32_t& endBlock) { // NOLINT
|
bool contiguousRange(uint32_t& bgnBlock, uint32_t& endBlock) {
|
||||||
return contiguousRange(&bgnBlock, &endBlock);
|
return contiguousRange(&bgnBlock, &endBlock);
|
||||||
}
|
}
|
||||||
/** \deprecated Use:
|
|
||||||
* bool createContiguous(SdBaseFile* dirFile,
|
/**
|
||||||
* const char* path, uint32_t size)
|
* \deprecated Use:
|
||||||
|
* bool createContiguous(SdBaseFile* dirFile, const char* path, uint32_t size)
|
||||||
* \param[in] dirFile The directory where the file will be created.
|
* \param[in] dirFile The directory where the file will be created.
|
||||||
* \param[in] path A path with a valid DOS 8.3 file name.
|
* \param[in] path A path with a valid DOS 8.3 file name.
|
||||||
* \param[in] size The desired file size.
|
* \param[in] size The desired file size.
|
||||||
* \return true for success or false for failure.
|
* \return true for success or false for failure.
|
||||||
*/
|
*/
|
||||||
bool createContiguous(SdBaseFile& dirFile, // NOLINT
|
bool createContiguous(SdBaseFile& dirFile, const char* path, uint32_t size) {
|
||||||
const char* path, uint32_t size) {
|
|
||||||
return createContiguous(&dirFile, path, size);
|
return createContiguous(&dirFile, path, size);
|
||||||
}
|
}
|
||||||
/** \deprecated Use:
|
|
||||||
|
/**
|
||||||
|
* \deprecated Use:
|
||||||
* static void dateTimeCallback(
|
* static void dateTimeCallback(
|
||||||
* void (*dateTime)(uint16_t* date, uint16_t* time));
|
* void (*dateTime)(uint16_t* date, uint16_t* time));
|
||||||
* \param[in] dateTime The user's call back function.
|
* \param[in] dateTime The user's call back function.
|
||||||
*/
|
*/
|
||||||
static void dateTimeCallback(
|
static void dateTimeCallback(
|
||||||
void (*dateTime)(uint16_t &date, uint16_t &time)) { // NOLINT
|
void (*dateTime)(uint16_t &date, uint16_t &time)) {
|
||||||
oldDateTime_ = dateTime;
|
oldDateTime_ = dateTime;
|
||||||
dateTime_ = dateTime ? oldToNew : 0;
|
dateTime_ = dateTime ? oldToNew : 0;
|
||||||
}
|
}
|
||||||
/** \deprecated Use: bool dirEntry(dir_t* dir);
|
|
||||||
* \param[out] dir Location for return of the file's directory entry.
|
/**
|
||||||
* \return true for success or false for failure.
|
* \deprecated Use:
|
||||||
*/
|
|
||||||
bool dirEntry(dir_t& dir) {return dirEntry(&dir);} // NOLINT
|
|
||||||
/** \deprecated Use:
|
|
||||||
* bool mkdir(SdBaseFile* dir, const char* path);
|
|
||||||
* \param[in] dir An open SdFat instance for the directory that will contain
|
|
||||||
* the new directory.
|
|
||||||
* \param[in] path A path with a valid 8.3 DOS name for the new directory.
|
|
||||||
* \return true for success or false for failure.
|
|
||||||
*/
|
|
||||||
bool mkdir(SdBaseFile& dir, const char* path) { // NOLINT
|
|
||||||
return mkdir(&dir, path);
|
|
||||||
}
|
|
||||||
/** \deprecated Use:
|
|
||||||
* bool open(SdBaseFile* dirFile, const char* path, uint8_t oflag);
|
* bool open(SdBaseFile* dirFile, const char* path, uint8_t oflag);
|
||||||
* \param[in] dirFile An open SdFat instance for the directory containing the
|
* \param[in] dirFile An open SdFat instance for the directory containing the
|
||||||
* file to be opened.
|
* file to be opened.
|
||||||
@@ -430,20 +433,23 @@ class SdBaseFile {
|
|||||||
* OR of flags O_READ, O_WRITE, O_TRUNC, and O_SYNC.
|
* OR of flags O_READ, O_WRITE, O_TRUNC, and O_SYNC.
|
||||||
* \return true for success or false for failure.
|
* \return true for success or false for failure.
|
||||||
*/
|
*/
|
||||||
bool open(SdBaseFile& dirFile, // NOLINT
|
bool open(SdBaseFile& dirFile, const char* path, uint8_t oflag) {
|
||||||
const char* path, uint8_t oflag) {
|
|
||||||
return open(&dirFile, path, oflag);
|
return open(&dirFile, path, oflag);
|
||||||
}
|
}
|
||||||
/** \deprecated Do not use in new apps
|
|
||||||
|
/**
|
||||||
|
* \deprecated Do not use in new apps
|
||||||
* \param[in] dirFile An open SdFat instance for the directory containing the
|
* \param[in] dirFile An open SdFat instance for the directory containing the
|
||||||
* file to be opened.
|
* file to be opened.
|
||||||
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
|
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
|
||||||
* \return true for success or false for failure.
|
* \return true for success or false for failure.
|
||||||
*/
|
*/
|
||||||
bool open(SdBaseFile& dirFile, const char* path) { // NOLINT
|
bool open(SdBaseFile& dirFile, const char* path) {
|
||||||
return open(dirFile, path, O_RDWR);
|
return open(dirFile, path, O_RDWR);
|
||||||
}
|
}
|
||||||
/** \deprecated Use:
|
|
||||||
|
/**
|
||||||
|
* \deprecated Use:
|
||||||
* bool open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag);
|
* bool open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag);
|
||||||
* \param[in] dirFile An open SdFat instance for the directory.
|
* \param[in] dirFile An open SdFat instance for the directory.
|
||||||
* \param[in] index The \a index of the directory entry for the file to be
|
* \param[in] index The \a index of the directory entry for the file to be
|
||||||
@@ -452,35 +458,39 @@ class SdBaseFile {
|
|||||||
* OR of flags O_READ, O_WRITE, O_TRUNC, and O_SYNC.
|
* OR of flags O_READ, O_WRITE, O_TRUNC, and O_SYNC.
|
||||||
* \return true for success or false for failure.
|
* \return true for success or false for failure.
|
||||||
*/
|
*/
|
||||||
bool open(SdBaseFile& dirFile, uint16_t index, uint8_t oflag) { // NOLINT
|
bool open(SdBaseFile& dirFile, uint16_t index, uint8_t oflag) {
|
||||||
return open(&dirFile, index, oflag);
|
return open(&dirFile, index, oflag);
|
||||||
}
|
}
|
||||||
/** \deprecated Use: bool openRoot(SdVolume* vol);
|
|
||||||
|
/**
|
||||||
|
* \deprecated Use: bool openRoot(SdVolume* vol);
|
||||||
* \param[in] vol The FAT volume containing the root directory to be opened.
|
* \param[in] vol The FAT volume containing the root directory to be opened.
|
||||||
* \return true for success or false for failure.
|
* \return true for success or false for failure.
|
||||||
*/
|
*/
|
||||||
bool openRoot(SdVolume& vol) {return openRoot(&vol);} // NOLINT
|
bool openRoot(SdVolume& vol) { return openRoot(&vol); }
|
||||||
/** \deprecated Use: int8_t readDir(dir_t* dir);
|
|
||||||
|
/**
|
||||||
|
* \deprecated Use: int8_t readDir(dir_t* dir);
|
||||||
* \param[out] dir The dir_t struct that will receive the data.
|
* \param[out] dir The dir_t struct that will receive the data.
|
||||||
* \return bytes read for success zero for eof or -1 for failure.
|
* \return bytes read for success zero for eof or -1 for failure.
|
||||||
*/
|
*/
|
||||||
int8_t readDir(dir_t& dir, char* longFilename) {return readDir(&dir, longFilename);} // NOLINT
|
int8_t readDir(dir_t& dir, char* longFilename) {
|
||||||
/** \deprecated Use:
|
return readDir(&dir, longFilename);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \deprecated Use:
|
||||||
* static uint8_t remove(SdBaseFile* dirFile, const char* path);
|
* static uint8_t remove(SdBaseFile* dirFile, const char* path);
|
||||||
* \param[in] dirFile The directory that contains the file.
|
* \param[in] dirFile The directory that contains the file.
|
||||||
* \param[in] path The name of the file to be removed.
|
* \param[in] path The name of the file to be removed.
|
||||||
* \return true for success or false for failure.
|
* \return true for success or false for failure.
|
||||||
*/
|
*/
|
||||||
static bool remove(SdBaseFile& dirFile, const char* path) { // NOLINT
|
static bool remove(SdBaseFile& dirFile, const char* path) { return remove(&dirFile, path); }
|
||||||
return remove(&dirFile, path);
|
|
||||||
}
|
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// rest are private
|
|
||||||
private:
|
private:
|
||||||
static void (*oldDateTime_)(uint16_t &date, uint16_t &time); // NOLINT
|
static void (*oldDateTime_)(uint16_t &date, uint16_t &time);
|
||||||
static void oldToNew(uint16_t* date, uint16_t* time) {
|
static void oldToNew(uint16_t * const date, uint16_t * const time) {
|
||||||
uint16_t d;
|
uint16_t d, t;
|
||||||
uint16_t t;
|
|
||||||
oldDateTime_(d, t);
|
oldDateTime_(d, t);
|
||||||
*date = d;
|
*date = d;
|
||||||
*time = t;
|
*time = t;
|
||||||
@@ -488,5 +498,4 @@ class SdBaseFile {
|
|||||||
#endif // ALLOW_DEPRECATED_FUNCTIONS
|
#endif // ALLOW_DEPRECATED_FUNCTIONS
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // SdBaseFile_h
|
#endif // _SDBASEFILE_H_
|
||||||
#endif
|
|
||||||
|
|||||||
@@ -21,32 +21,28 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* SdFatConfig.h
|
||||||
* Arduino SdFat Library
|
* Arduino SdFat Library
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Copyright (C) 2009 by William Greiman
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
/**
|
|
||||||
* \file
|
|
||||||
* \brief configuration definitions
|
|
||||||
*/
|
|
||||||
#include "Marlin.h"
|
|
||||||
#if ENABLED(SDSUPPORT)
|
|
||||||
|
|
||||||
#ifndef SdFatConfig_h
|
#ifndef _SDFATCONFIG_H_
|
||||||
#define SdFatConfig_h
|
#define _SDFATCONFIG_H_
|
||||||
#include <stdint.h>
|
|
||||||
//------------------------------------------------------------------------------
|
#include "MarlinConfig.h"
|
||||||
/**
|
|
||||||
|
/**
|
||||||
* To use multiple SD cards set USE_MULTIPLE_CARDS nonzero.
|
* To use multiple SD cards set USE_MULTIPLE_CARDS nonzero.
|
||||||
*
|
*
|
||||||
* Using multiple cards costs 400 - 500 bytes of flash.
|
* Using multiple cards costs 400 - 500 bytes of flash.
|
||||||
*
|
*
|
||||||
* Each card requires about 550 bytes of SRAM so use of a Mega is recommended.
|
* Each card requires about 550 bytes of SRAM so use of a Mega is recommended.
|
||||||
*/
|
*/
|
||||||
#define USE_MULTIPLE_CARDS 0
|
#define USE_MULTIPLE_CARDS 0
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* Call flush for endl if ENDL_CALLS_FLUSH is nonzero
|
* Call flush for endl if ENDL_CALLS_FLUSH is nonzero
|
||||||
*
|
*
|
||||||
* The standard for iostreams is to call flush. This is very costly for
|
* The standard for iostreams is to call flush. This is very costly for
|
||||||
@@ -63,32 +59,32 @@
|
|||||||
* If ENDL_CALLS_FLUSH is zero, you must call flush and/or close to force
|
* If ENDL_CALLS_FLUSH is zero, you must call flush and/or close to force
|
||||||
* all data to be written to the SD.
|
* all data to be written to the SD.
|
||||||
*/
|
*/
|
||||||
#define ENDL_CALLS_FLUSH 0
|
#define ENDL_CALLS_FLUSH 0
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* Allow use of deprecated functions if ALLOW_DEPRECATED_FUNCTIONS is nonzero
|
* Allow use of deprecated functions if ALLOW_DEPRECATED_FUNCTIONS is nonzero
|
||||||
*/
|
*/
|
||||||
#define ALLOW_DEPRECATED_FUNCTIONS 1
|
#define ALLOW_DEPRECATED_FUNCTIONS 1
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* Allow FAT12 volumes if FAT12_SUPPORT is nonzero.
|
* Allow FAT12 volumes if FAT12_SUPPORT is nonzero.
|
||||||
* FAT12 has not been well tested.
|
* FAT12 has not been well tested.
|
||||||
*/
|
*/
|
||||||
#define FAT12_SUPPORT 0
|
#define FAT12_SUPPORT 0
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* SPI init rate for SD initialization commands. Must be 5 (F_CPU/64)
|
* SPI init rate for SD initialization commands. Must be 5 (F_CPU/64)
|
||||||
* or 6 (F_CPU/128).
|
* or 6 (F_CPU/128).
|
||||||
*/
|
*/
|
||||||
#define SPI_SD_INIT_RATE 5
|
#define SPI_SD_INIT_RATE 5
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* Set the SS pin high for hardware SPI. If SS is chip select for another SPI
|
* Set the SS pin high for hardware SPI. If SS is chip select for another SPI
|
||||||
* device this will disable that device during the SD init phase.
|
* device this will disable that device during the SD init phase.
|
||||||
*/
|
*/
|
||||||
#define SET_SPI_SS_HIGH 1
|
#define SET_SPI_SS_HIGH 1
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* Define MEGA_SOFT_SPI nonzero to use software SPI on Mega Arduinos.
|
* Define MEGA_SOFT_SPI nonzero to use software SPI on Mega Arduinos.
|
||||||
* Pins used are SS 10, MOSI 11, MISO 12, and SCK 13.
|
* Pins used are SS 10, MOSI 11, MISO 12, and SCK 13.
|
||||||
*
|
*
|
||||||
@@ -96,39 +92,30 @@
|
|||||||
* on Mega Arduinos. Software SPI works well with GPS Shield V1.1
|
* on Mega Arduinos. Software SPI works well with GPS Shield V1.1
|
||||||
* but many SD cards will fail with GPS Shield V1.0.
|
* but many SD cards will fail with GPS Shield V1.0.
|
||||||
*/
|
*/
|
||||||
#define MEGA_SOFT_SPI 0
|
#define MEGA_SOFT_SPI 0
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
// Set USE_SOFTWARE_SPI nonzero to ALWAYS use Software SPI.
|
||||||
* Set USE_SOFTWARE_SPI nonzero to always use software SPI.
|
#define USE_SOFTWARE_SPI 0
|
||||||
*/
|
|
||||||
#define USE_SOFTWARE_SPI 0
|
// Define software SPI pins so Mega can use unmodified 168/328 shields
|
||||||
// define software SPI pins so Mega can use unmodified 168/328 shields
|
#define SOFT_SPI_CS_PIN 10 // Software SPI chip select pin for the SD
|
||||||
/** Software SPI chip select pin for the SD */
|
#define SOFT_SPI_MOSI_PIN 11 // Software SPI Master Out Slave In pin
|
||||||
#define SOFT_SPI_CS_PIN 10
|
#define SOFT_SPI_MISO_PIN 12 // Software SPI Master In Slave Out pin
|
||||||
/** Software SPI Master Out Slave In pin */
|
#define SOFT_SPI_SCK_PIN 13 // Software SPI Clock pin
|
||||||
#define SOFT_SPI_MOSI_PIN 11
|
|
||||||
/** Software SPI Master In Slave Out pin */
|
/**
|
||||||
#define SOFT_SPI_MISO_PIN 12
|
|
||||||
/** Software SPI Clock pin */
|
|
||||||
#define SOFT_SPI_SCK_PIN 13
|
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
|
||||||
* The __cxa_pure_virtual function is an error handler that is invoked when
|
* The __cxa_pure_virtual function is an error handler that is invoked when
|
||||||
* a pure virtual function is called.
|
* a pure virtual function is called.
|
||||||
*/
|
*/
|
||||||
#define USE_CXA_PURE_VIRTUAL 1
|
#define USE_CXA_PURE_VIRTUAL 1
|
||||||
|
|
||||||
/** Number of UTF-16 characters per entry */
|
/**
|
||||||
#define FILENAME_LENGTH 13
|
* Defines for 8.3 and long (vfat) filenames
|
||||||
|
|
||||||
/**
|
|
||||||
* Defines for long (vfat) filenames
|
|
||||||
*/
|
*/
|
||||||
/** Number of VFAT entries used. Every entry has 13 UTF-16 characters */
|
|
||||||
#define MAX_VFAT_ENTRIES (2)
|
|
||||||
/** Total size of the buffer used to store the long filenames */
|
|
||||||
#define LONG_FILENAME_LENGTH (FILENAME_LENGTH*MAX_VFAT_ENTRIES+1)
|
|
||||||
#endif // SdFatConfig_h
|
|
||||||
|
|
||||||
|
#define FILENAME_LENGTH 13 // Number of UTF-16 characters per entry
|
||||||
|
|
||||||
#endif
|
// Total bytes needed to store a single long filename
|
||||||
|
#define LONG_FILENAME_LENGTH (FILENAME_LENGTH * MAX_VFAT_ENTRIES + 1)
|
||||||
|
|
||||||
|
#endif // _SDFATCONFIG_H_
|
||||||
|
|||||||
@@ -20,35 +20,31 @@
|
|||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \file
|
||||||
|
* \brief FAT file structures
|
||||||
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Arduino SdFat Library
|
* Arduino SdFat Library
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Copyright (C) 2009 by William Greiman
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#ifndef SDFATSTRUCTS_H
|
||||||
#if ENABLED(SDSUPPORT)
|
#define SDFATSTRUCTS_H
|
||||||
|
|
||||||
#ifndef SdFatStructs_h
|
|
||||||
#define SdFatStructs_h
|
|
||||||
|
|
||||||
#define PACKED __attribute__((__packed__))
|
#define PACKED __attribute__((__packed__))
|
||||||
/**
|
|
||||||
* \file
|
|
||||||
* \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
|
||||||
*/
|
*/
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Value for byte 510 of boot block or MBR */
|
uint8_t const BOOTSIG0 = 0x55, // Value for byte 510 of boot block or MBR
|
||||||
uint8_t const BOOTSIG0 = 0x55;
|
BOOTSIG1 = 0xAA, // Value for byte 511 of boot block or MBR
|
||||||
/** Value for byte 511 of boot block or MBR */
|
EXTENDED_BOOT_SIG = 0x29; // Value for bootSignature field int FAT/FAT32 boot sector
|
||||||
uint8_t const BOOTSIG1 = 0xAA;
|
|
||||||
/** Value for bootSignature field int FAT/FAT32 boot sector */
|
|
||||||
uint8_t const EXTENDED_BOOT_SIG = 0x29;
|
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* \struct partitionTable
|
* \struct partitionTable
|
||||||
* \brief MBR partition table entry
|
* \brief MBR partition table entry
|
||||||
@@ -102,14 +98,13 @@ struct partitionTable {
|
|||||||
* are 0-1023. Only used in old PC BIOS.
|
* are 0-1023. Only used in old PC BIOS.
|
||||||
*/
|
*/
|
||||||
uint8_t endCylinderLow;
|
uint8_t endCylinderLow;
|
||||||
/** Logical block address of the first block in the partition. */
|
|
||||||
uint32_t firstSector;
|
uint32_t firstSector; // Logical block address of the first block in the partition.
|
||||||
/** Length of the partition, in blocks. */
|
uint32_t totalSectors; // Length of the partition, in blocks.
|
||||||
uint32_t totalSectors;
|
|
||||||
} PACKED;
|
} PACKED;
|
||||||
/** Type name for partitionTable */
|
|
||||||
typedef struct partitionTable part_t;
|
typedef struct partitionTable part_t; // Type name for partitionTable
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* \struct masterBootRecord
|
* \struct masterBootRecord
|
||||||
*
|
*
|
||||||
@@ -118,22 +113,16 @@ typedef struct partitionTable part_t;
|
|||||||
* The first block of a storage device that is formatted with a MBR.
|
* The first block of a storage device that is formatted with a MBR.
|
||||||
*/
|
*/
|
||||||
struct masterBootRecord {
|
struct masterBootRecord {
|
||||||
/** Code Area for master boot program. */
|
uint8_t codeArea[440]; // Code Area for master boot program.
|
||||||
uint8_t codeArea[440];
|
uint32_t diskSignature; // Optional Windows NT disk signature. May contain boot code.
|
||||||
/** Optional Windows NT disk signature. May contain boot code. */
|
uint16_t usuallyZero; // Usually zero but may be more boot code.
|
||||||
uint32_t diskSignature;
|
part_t part[4]; // Partition tables.
|
||||||
/** Usually zero but may be more boot code. */
|
uint8_t mbrSig0; // First MBR signature byte. Must be 0x55
|
||||||
uint16_t usuallyZero;
|
uint8_t mbrSig1; // Second MBR signature byte. Must be 0xAA
|
||||||
/** Partition tables. */
|
|
||||||
part_t part[4];
|
|
||||||
/** First MBR signature byte. Must be 0x55 */
|
|
||||||
uint8_t mbrSig0;
|
|
||||||
/** Second MBR signature byte. Must be 0xAA */
|
|
||||||
uint8_t mbrSig1;
|
|
||||||
} PACKED;
|
} PACKED;
|
||||||
/** Type name for masterBootRecord */
|
/** Type name for masterBootRecord */
|
||||||
typedef struct masterBootRecord mbr_t;
|
typedef struct masterBootRecord mbr_t;
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* \struct fat_boot
|
* \struct fat_boot
|
||||||
*
|
*
|
||||||
@@ -206,10 +195,10 @@ struct fat_boot {
|
|||||||
* contains the FAT size count.
|
* contains the FAT size count.
|
||||||
*/
|
*/
|
||||||
uint16_t sectorsPerFat16;
|
uint16_t sectorsPerFat16;
|
||||||
/** Sectors per track for interrupt 0x13. Not used otherwise. */
|
|
||||||
uint16_t sectorsPerTrack;
|
uint16_t sectorsPerTrack; // Sectors per track for interrupt 0x13. Not used otherwise.
|
||||||
/** Number of heads for interrupt 0x13. Not used otherwise. */
|
uint16_t headCount; // Number of heads for interrupt 0x13. Not used otherwise.
|
||||||
uint16_t headCount;
|
|
||||||
/**
|
/**
|
||||||
* Count of hidden sectors preceding the partition that contains this
|
* Count of hidden sectors preceding the partition that contains this
|
||||||
* FAT volume. This field is generally only relevant for media
|
* FAT volume. This field is generally only relevant for media
|
||||||
@@ -232,10 +221,10 @@ struct fat_boot {
|
|||||||
* relevant if the device is a boot device.
|
* relevant if the device is a boot device.
|
||||||
*/
|
*/
|
||||||
uint8_t driveNumber;
|
uint8_t driveNumber;
|
||||||
/** used by Windows NT - should be zero for FAT */
|
|
||||||
uint8_t reserved1;
|
uint8_t reserved1; // used by Windows NT - should be zero for FAT
|
||||||
/** 0x29 if next three fields are valid */
|
uint8_t bootSignature; // 0x29 if next three fields are valid
|
||||||
uint8_t bootSignature;
|
|
||||||
/**
|
/**
|
||||||
* A random serial number created when formatting a disk,
|
* A random serial number created when formatting a disk,
|
||||||
* which helps to distinguish between disks.
|
* which helps to distinguish between disks.
|
||||||
@@ -252,21 +241,18 @@ struct fat_boot {
|
|||||||
* depending on the disk format.
|
* depending on the disk format.
|
||||||
*/
|
*/
|
||||||
char fileSystemType[8];
|
char fileSystemType[8];
|
||||||
/** X86 boot code */
|
|
||||||
uint8_t bootCode[448];
|
uint8_t bootCode[448]; // X86 boot code
|
||||||
/** must be 0x55 */
|
uint8_t bootSectorSig0; // must be 0x55
|
||||||
uint8_t bootSectorSig0;
|
uint8_t bootSectorSig1; // must be 0xAA
|
||||||
/** must be 0xAA */
|
|
||||||
uint8_t bootSectorSig1;
|
|
||||||
} PACKED;
|
} PACKED;
|
||||||
/** Type name for FAT Boot Sector */
|
|
||||||
typedef struct fat_boot fat_boot_t;
|
typedef struct fat_boot fat_boot_t; // Type name for FAT Boot Sector
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* \struct fat32_boot
|
* \struct fat32_boot
|
||||||
*
|
*
|
||||||
* \brief Boot sector for a FAT32 volume.
|
* \brief Boot sector for a FAT32 volume.
|
||||||
*
|
|
||||||
*/
|
*/
|
||||||
struct fat32_boot {
|
struct fat32_boot {
|
||||||
/**
|
/**
|
||||||
@@ -322,10 +308,10 @@ struct fat32_boot {
|
|||||||
* contains the FAT size count.
|
* contains the FAT size count.
|
||||||
*/
|
*/
|
||||||
uint16_t sectorsPerFat16;
|
uint16_t sectorsPerFat16;
|
||||||
/** Sectors per track for interrupt 0x13. Not used otherwise. */
|
|
||||||
uint16_t sectorsPerTrack;
|
uint16_t sectorsPerTrack; // Sectors per track for interrupt 0x13. Not used otherwise.
|
||||||
/** Number of heads for interrupt 0x13. Not used otherwise. */
|
uint16_t headCount; // Number of heads for interrupt 0x13. Not used otherwise.
|
||||||
uint16_t headCount;
|
|
||||||
/**
|
/**
|
||||||
* Count of hidden sectors preceding the partition that contains this
|
* Count of hidden sectors preceding the partition that contains this
|
||||||
* FAT volume. This field is generally only relevant for media
|
* FAT volume. This field is generally only relevant for media
|
||||||
@@ -387,10 +373,10 @@ struct fat32_boot {
|
|||||||
* relevant if the device is a boot device.
|
* relevant if the device is a boot device.
|
||||||
*/
|
*/
|
||||||
uint8_t driveNumber;
|
uint8_t driveNumber;
|
||||||
/** used by Windows NT - should be zero for FAT */
|
|
||||||
uint8_t reserved1;
|
uint8_t reserved1; // Used by Windows NT - should be zero for FAT
|
||||||
/** 0x29 if next three fields are valid */
|
uint8_t bootSignature; // 0x29 if next three fields are valid
|
||||||
uint8_t bootSignature;
|
|
||||||
/**
|
/**
|
||||||
* A random serial number created when formatting a disk,
|
* A random serial number created when formatting a disk,
|
||||||
* which helps to distinguish between disks.
|
* which helps to distinguish between disks.
|
||||||
@@ -406,20 +392,18 @@ struct fat32_boot {
|
|||||||
* A text field with a value of FAT32.
|
* A text field with a value of FAT32.
|
||||||
*/
|
*/
|
||||||
char fileSystemType[8];
|
char fileSystemType[8];
|
||||||
/** X86 boot code */
|
|
||||||
uint8_t bootCode[420];
|
uint8_t bootCode[420]; // X86 boot code
|
||||||
/** must be 0x55 */
|
uint8_t bootSectorSig0; // must be 0x55
|
||||||
uint8_t bootSectorSig0;
|
uint8_t bootSectorSig1; // must be 0xAA
|
||||||
/** must be 0xAA */
|
|
||||||
uint8_t bootSectorSig1;
|
|
||||||
} PACKED;
|
} PACKED;
|
||||||
/** Type name for FAT32 Boot Sector */
|
|
||||||
typedef struct fat32_boot fat32_boot_t;
|
typedef struct fat32_boot fat32_boot_t; // Type name for FAT32 Boot Sector
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Lead signature for a FSINFO sector */
|
uint32_t const FSINFO_LEAD_SIG = 0x41615252, // 'AaRR' Lead signature for a FSINFO sector
|
||||||
uint32_t const FSINFO_LEAD_SIG = 0x41615252;
|
FSINFO_STRUCT_SIG = 0x61417272; // 'aArr' Struct signature for a FSINFO sector
|
||||||
/** Struct signature for a FSINFO sector */
|
|
||||||
uint32_t const FSINFO_STRUCT_SIG = 0x61417272;
|
|
||||||
/**
|
/**
|
||||||
* \struct fat32_fsinfo
|
* \struct fat32_fsinfo
|
||||||
*
|
*
|
||||||
@@ -427,12 +411,9 @@ uint32_t const FSINFO_STRUCT_SIG = 0x61417272;
|
|||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
struct fat32_fsinfo {
|
struct fat32_fsinfo {
|
||||||
/** must be 0x52, 0x52, 0x61, 0x41 */
|
uint32_t leadSignature; // must be 0x52, 0x52, 0x61, 0x41 'RRaA'
|
||||||
uint32_t leadSignature;
|
uint8_t reserved1[480]; // must be zero
|
||||||
/** must be zero */
|
uint32_t structSignature; // must be 0x72, 0x72, 0x41, 0x61 'rrAa'
|
||||||
uint8_t reserved1[480];
|
|
||||||
/** must be 0x72, 0x72, 0x41, 0x61 */
|
|
||||||
uint32_t structSignature;
|
|
||||||
/**
|
/**
|
||||||
* Contains the last known free cluster count on the volume.
|
* Contains the last known free cluster count on the volume.
|
||||||
* If the value is 0xFFFFFFFF, then the free count is unknown
|
* If the value is 0xFFFFFFFF, then the free count is unknown
|
||||||
@@ -448,30 +429,22 @@ struct fat32_fsinfo {
|
|||||||
* should start looking at cluster 2.
|
* should start looking at cluster 2.
|
||||||
*/
|
*/
|
||||||
uint32_t nextFree;
|
uint32_t nextFree;
|
||||||
/** must be zero */
|
|
||||||
uint8_t reserved2[12];
|
uint8_t reserved2[12]; // must be zero
|
||||||
/** must be 0x00, 0x00, 0x55, 0xAA */
|
uint8_t tailSignature[4]; // must be 0x00, 0x00, 0x55, 0xAA
|
||||||
uint8_t tailSignature[4];
|
|
||||||
} PACKED;
|
} PACKED;
|
||||||
/** Type name for FAT32 FSINFO Sector */
|
|
||||||
typedef struct fat32_fsinfo fat32_fsinfo_t;
|
typedef struct fat32_fsinfo fat32_fsinfo_t; // Type name for FAT32 FSINFO Sector
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// End Of Chain values for FAT entries
|
// End Of Chain values for FAT entries
|
||||||
/** FAT12 end of chain value used by Microsoft. */
|
uint16_t const FAT12EOC = 0xFFF, // FAT12 end of chain value used by Microsoft.
|
||||||
uint16_t const FAT12EOC = 0xFFF;
|
FAT12EOC_MIN = 0xFF8, // Minimum value for FAT12 EOC. Use to test for EOC.
|
||||||
/** Minimum value for FAT12 EOC. Use to test for EOC. */
|
FAT16EOC = 0xFFFF, // FAT16 end of chain value used by Microsoft.
|
||||||
uint16_t const FAT12EOC_MIN = 0xFF8;
|
FAT16EOC_MIN = 0xFFF8; // Minimum value for FAT16 EOC. Use to test for EOC.
|
||||||
/** FAT16 end of chain value used by Microsoft. */
|
uint32_t const FAT32EOC = 0x0FFFFFFF, // FAT32 end of chain value used by Microsoft.
|
||||||
uint16_t const FAT16EOC = 0xFFFF;
|
FAT32EOC_MIN = 0x0FFFFFF8, // Minimum value for FAT32 EOC. Use to test for EOC.
|
||||||
/** Minimum value for FAT16 EOC. Use to test for EOC. */
|
FAT32MASK = 0x0FFFFFFF; // Mask a for FAT32 entry. Entries are 28 bits.
|
||||||
uint16_t const FAT16EOC_MIN = 0xFFF8;
|
|
||||||
/** FAT32 end of chain value used by Microsoft. */
|
|
||||||
uint32_t const FAT32EOC = 0x0FFFFFFF;
|
|
||||||
/** Minimum value for FAT32 EOC. Use to test for EOC. */
|
|
||||||
uint32_t const FAT32EOC_MIN = 0x0FFFFFF8;
|
|
||||||
/** Mask a for FAT32 entry. Entries are 28 bits. */
|
|
||||||
uint32_t const FAT32MASK = 0x0FFFFFFF;
|
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* \struct directoryEntry
|
* \struct directoryEntry
|
||||||
* \brief FAT short directory entry
|
* \brief FAT short directory entry
|
||||||
@@ -503,13 +476,15 @@ uint32_t const FAT32MASK = 0x0FFFFFFF;
|
|||||||
* The valid time range is from Midnight 00:00:00 to 23:59:58.
|
* The valid time range is from Midnight 00:00:00 to 23:59:58.
|
||||||
*/
|
*/
|
||||||
struct directoryEntry {
|
struct directoryEntry {
|
||||||
/** Short 8.3 name.
|
/**
|
||||||
|
* Short 8.3 name.
|
||||||
*
|
*
|
||||||
* The first eight bytes contain the file name with blank fill.
|
* The first eight bytes contain the file name with blank fill.
|
||||||
* The last three bytes contain the file extension with blank fill.
|
* The last three bytes contain the file extension with blank fill.
|
||||||
*/
|
*/
|
||||||
uint8_t name[11];
|
uint8_t name[11];
|
||||||
/** Entry attributes.
|
/**
|
||||||
|
* Entry attributes.
|
||||||
*
|
*
|
||||||
* The upper two bits of the attribute byte are reserved and should
|
* The upper two bits of the attribute byte are reserved and should
|
||||||
* always be set to 0 when a file is created and never modified or
|
* always be set to 0 when a file is created and never modified or
|
||||||
@@ -527,10 +502,10 @@ struct directoryEntry {
|
|||||||
* value range is 0-199 inclusive. (WHG note - seems to be hundredths)
|
* value range is 0-199 inclusive. (WHG note - seems to be hundredths)
|
||||||
*/
|
*/
|
||||||
uint8_t creationTimeTenths;
|
uint8_t creationTimeTenths;
|
||||||
/** Time file was created. */
|
|
||||||
uint16_t creationTime;
|
uint16_t creationTime; // Time file was created.
|
||||||
/** Date file was created. */
|
uint16_t creationDate; // Date file was created.
|
||||||
uint16_t creationDate;
|
|
||||||
/**
|
/**
|
||||||
* Last access date. Note that there is no last access time, only
|
* Last access date. Note that there is no last access time, only
|
||||||
* a date. This is the date of last read or write. In the case of
|
* a date. This is the date of last read or write. In the case of
|
||||||
@@ -542,15 +517,13 @@ struct directoryEntry {
|
|||||||
* FAT12 or FAT16 volume).
|
* FAT12 or FAT16 volume).
|
||||||
*/
|
*/
|
||||||
uint16_t firstClusterHigh;
|
uint16_t firstClusterHigh;
|
||||||
/** Time of last write. File creation is considered a write. */
|
|
||||||
uint16_t lastWriteTime;
|
uint16_t lastWriteTime; // Time of last write. File creation is considered a write.
|
||||||
/** Date of last write. File creation is considered a write. */
|
uint16_t lastWriteDate; // Date of last write. File creation is considered a write.
|
||||||
uint16_t lastWriteDate;
|
uint16_t firstClusterLow; // Low word of this entry's first cluster number.
|
||||||
/** Low word of this entry's first cluster number. */
|
uint32_t fileSize; // 32-bit unsigned holding this file's size in bytes.
|
||||||
uint16_t firstClusterLow;
|
|
||||||
/** 32-bit unsigned holding this file's size in bytes. */
|
|
||||||
uint32_t fileSize;
|
|
||||||
} PACKED;
|
} PACKED;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* \struct directoryVFATEntry
|
* \struct directoryVFATEntry
|
||||||
* \brief VFAT long filename directory entry
|
* \brief VFAT long filename directory entry
|
||||||
@@ -568,54 +541,36 @@ struct directoryVFATEntry {
|
|||||||
* bit 0-4: the position of this long filename block (first block is 1)
|
* bit 0-4: the position of this long filename block (first block is 1)
|
||||||
*/
|
*/
|
||||||
uint8_t sequenceNumber;
|
uint8_t sequenceNumber;
|
||||||
/** First set of UTF-16 characters */
|
|
||||||
uint16_t name1[5];//UTF-16
|
uint16_t name1[5]; // First set of UTF-16 characters
|
||||||
/** attributes (at the same location as in directoryEntry), always 0x0F */
|
uint8_t attributes; // attributes (at the same location as in directoryEntry), always 0x0F
|
||||||
uint8_t attributes;
|
uint8_t reservedNT; // Reserved for use by Windows NT. Always 0.
|
||||||
/** Reserved for use by Windows NT. Always 0. */
|
uint8_t checksum; // Checksum of the short 8.3 filename, can be used to checked if the file system as modified by a not-long-filename aware implementation.
|
||||||
uint8_t reservedNT;
|
uint16_t name2[6]; // Second set of UTF-16 characters
|
||||||
/** Checksum of the short 8.3 filename, can be used to checked if the file system as modified by a not-long-filename aware implementation. */
|
uint16_t firstClusterLow; // firstClusterLow is always zero for longFilenames
|
||||||
uint8_t checksum;
|
uint16_t name3[2]; // Third set of UTF-16 characters
|
||||||
/** Second set of UTF-16 characters */
|
|
||||||
uint16_t name2[6];//UTF-16
|
|
||||||
/** firstClusterLow is always zero for longFilenames */
|
|
||||||
uint16_t firstClusterLow;
|
|
||||||
/** Third set of UTF-16 characters */
|
|
||||||
uint16_t name3[2];//UTF-16
|
|
||||||
} PACKED;
|
} PACKED;
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// Definitions for directory entries
|
// Definitions for directory entries
|
||||||
//
|
//
|
||||||
/** Type name for directoryEntry */
|
typedef struct directoryEntry dir_t; // Type name for directoryEntry
|
||||||
typedef struct directoryEntry dir_t;
|
typedef struct directoryVFATEntry vfat_t; // Type name for directoryVFATEntry
|
||||||
/** Type name for directoryVFATEntry */
|
|
||||||
typedef struct directoryVFATEntry vfat_t;
|
uint8_t const DIR_NAME_0xE5 = 0x05, // escape for name[0] = 0xE5
|
||||||
/** escape for name[0] = 0xE5 */
|
DIR_NAME_DELETED = 0xE5, // name[0] value for entry that is free after being "deleted"
|
||||||
uint8_t const DIR_NAME_0xE5 = 0x05;
|
DIR_NAME_FREE = 0x00, // name[0] value for entry that is free and no allocated entries follow
|
||||||
/** name[0] value for entry that is free after being "deleted" */
|
DIR_ATT_READ_ONLY = 0x01, // file is read-only
|
||||||
uint8_t const DIR_NAME_DELETED = 0xE5;
|
DIR_ATT_HIDDEN = 0x02, // File should hidden in directory listings
|
||||||
/** name[0] value for entry that is free and no allocated entries follow */
|
DIR_ATT_SYSTEM = 0x04, // Entry is for a system file
|
||||||
uint8_t const DIR_NAME_FREE = 0x00;
|
DIR_ATT_VOLUME_ID = 0x08, // Directory entry contains the volume label
|
||||||
/** file is read-only */
|
DIR_ATT_DIRECTORY = 0x10, // Entry is for a directory
|
||||||
uint8_t const DIR_ATT_READ_ONLY = 0x01;
|
DIR_ATT_ARCHIVE = 0x20, // Old DOS archive bit for backup support
|
||||||
/** File should hidden in directory listings */
|
DIR_ATT_LONG_NAME = 0x0F, // Test value for long name entry. Test is (d->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME.
|
||||||
uint8_t const DIR_ATT_HIDDEN = 0x02;
|
DIR_ATT_LONG_NAME_MASK = 0x3F, // Test mask for long name entry
|
||||||
/** Entry is for a system file */
|
DIR_ATT_DEFINED_BITS = 0x3F; // defined attribute bits
|
||||||
uint8_t const DIR_ATT_SYSTEM = 0x04;
|
|
||||||
/** Directory entry contains the volume label */
|
/**
|
||||||
uint8_t const DIR_ATT_VOLUME_ID = 0x08;
|
* Directory entry is part of a long name
|
||||||
/** Entry is for a directory */
|
|
||||||
uint8_t const DIR_ATT_DIRECTORY = 0x10;
|
|
||||||
/** Old DOS archive bit for backup support */
|
|
||||||
uint8_t const DIR_ATT_ARCHIVE = 0x20;
|
|
||||||
/** Test value for long name entry. Test is
|
|
||||||
(d->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME. */
|
|
||||||
uint8_t const DIR_ATT_LONG_NAME = 0x0F;
|
|
||||||
/** Test mask for long name entry */
|
|
||||||
uint8_t const DIR_ATT_LONG_NAME_MASK = 0x3F;
|
|
||||||
/** defined attribute bits */
|
|
||||||
uint8_t const DIR_ATT_DEFINED_BITS = 0x3F;
|
|
||||||
/** Directory entry is part of a long name
|
|
||||||
* \param[in] dir Pointer to a directory entry.
|
* \param[in] dir Pointer to a directory entry.
|
||||||
*
|
*
|
||||||
* \return true if the entry is for part of a long name else false.
|
* \return true if the entry is for part of a long name else false.
|
||||||
@@ -623,9 +578,12 @@ uint8_t const DIR_ATT_DEFINED_BITS = 0x3F;
|
|||||||
static inline uint8_t DIR_IS_LONG_NAME(const dir_t* dir) {
|
static inline uint8_t DIR_IS_LONG_NAME(const dir_t* dir) {
|
||||||
return (dir->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME;
|
return (dir->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME;
|
||||||
}
|
}
|
||||||
|
|
||||||
/** Mask for file/subdirectory tests */
|
/** Mask for file/subdirectory tests */
|
||||||
uint8_t const DIR_ATT_FILE_TYPE_MASK = (DIR_ATT_VOLUME_ID | DIR_ATT_DIRECTORY);
|
uint8_t const DIR_ATT_FILE_TYPE_MASK = (DIR_ATT_VOLUME_ID | DIR_ATT_DIRECTORY);
|
||||||
/** Directory entry is for a file
|
|
||||||
|
/**
|
||||||
|
* Directory entry is for a file
|
||||||
* \param[in] dir Pointer to a directory entry.
|
* \param[in] dir Pointer to a directory entry.
|
||||||
*
|
*
|
||||||
* \return true if the entry is for a normal file else false.
|
* \return true if the entry is for a normal file else false.
|
||||||
@@ -633,7 +591,9 @@ uint8_t const DIR_ATT_FILE_TYPE_MASK = (DIR_ATT_VOLUME_ID | DIR_ATT_DIRECTORY);
|
|||||||
static inline uint8_t DIR_IS_FILE(const dir_t* dir) {
|
static inline uint8_t DIR_IS_FILE(const dir_t* dir) {
|
||||||
return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == 0;
|
return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == 0;
|
||||||
}
|
}
|
||||||
/** Directory entry is for a subdirectory
|
|
||||||
|
/**
|
||||||
|
* Directory entry is for a subdirectory
|
||||||
* \param[in] dir Pointer to a directory entry.
|
* \param[in] dir Pointer to a directory entry.
|
||||||
*
|
*
|
||||||
* \return true if the entry is for a subdirectory else false.
|
* \return true if the entry is for a subdirectory else false.
|
||||||
@@ -641,7 +601,9 @@ static inline uint8_t DIR_IS_FILE(const dir_t* dir) {
|
|||||||
static inline uint8_t DIR_IS_SUBDIR(const dir_t* dir) {
|
static inline uint8_t DIR_IS_SUBDIR(const dir_t* dir) {
|
||||||
return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == DIR_ATT_DIRECTORY;
|
return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == DIR_ATT_DIRECTORY;
|
||||||
}
|
}
|
||||||
/** Directory entry is for a file or subdirectory
|
|
||||||
|
/**
|
||||||
|
* Directory entry is for a file or subdirectory
|
||||||
* \param[in] dir Pointer to a directory entry.
|
* \param[in] dir Pointer to a directory entry.
|
||||||
*
|
*
|
||||||
* \return true if the entry is for a normal file or subdirectory else false.
|
* \return true if the entry is for a normal file or subdirectory else false.
|
||||||
@@ -649,7 +611,5 @@ static inline uint8_t DIR_IS_SUBDIR(const dir_t* dir) {
|
|||||||
static inline uint8_t DIR_IS_FILE_OR_SUBDIR(const dir_t* dir) {
|
static inline uint8_t DIR_IS_FILE_OR_SUBDIR(const dir_t* dir) {
|
||||||
return (dir->attributes & DIR_ATT_VOLUME_ID) == 0;
|
return (dir->attributes & DIR_ATT_VOLUME_ID) == 0;
|
||||||
}
|
}
|
||||||
#endif // SdFatStructs_h
|
|
||||||
|
|
||||||
|
#endif // SDFATSTRUCTS_H
|
||||||
#endif
|
|
||||||
|
|||||||
@@ -26,13 +26,15 @@
|
|||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#include "MarlinConfig.h"
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
#include "SdFatUtil.h"
|
|
||||||
|
|
||||||
//------------------------------------------------------------------------------
|
#include "SdFatUtil.h"
|
||||||
/** Amount of free RAM
|
#include "serial.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Amount of free RAM
|
||||||
* \return The number of free bytes.
|
* \return The number of free bytes.
|
||||||
*/
|
*/
|
||||||
#ifdef __arm__
|
#ifdef __arm__
|
||||||
@@ -44,7 +46,8 @@ int SdFatUtil::FreeRam() {
|
|||||||
#else // __arm__
|
#else // __arm__
|
||||||
extern char* __brkval;
|
extern char* __brkval;
|
||||||
extern char __bss_end;
|
extern char __bss_end;
|
||||||
/** Amount of free RAM
|
/**
|
||||||
|
* Amount of free RAM
|
||||||
* \return The number of free bytes.
|
* \return The number of free bytes.
|
||||||
*/
|
*/
|
||||||
int SdFatUtil::FreeRam() {
|
int SdFatUtil::FreeRam() {
|
||||||
@@ -53,8 +56,8 @@ int SdFatUtil::FreeRam() {
|
|||||||
}
|
}
|
||||||
#endif // __arm
|
#endif // __arm
|
||||||
|
|
||||||
//------------------------------------------------------------------------------
|
/**
|
||||||
/** %Print a string in flash memory.
|
* %Print a string in flash memory.
|
||||||
*
|
*
|
||||||
* \param[in] pr Print object for output.
|
* \param[in] pr Print object for output.
|
||||||
* \param[in] str Pointer to string stored in flash memory.
|
* \param[in] str Pointer to string stored in flash memory.
|
||||||
@@ -62,30 +65,27 @@ int SdFatUtil::FreeRam() {
|
|||||||
void SdFatUtil::print_P(PGM_P str) {
|
void SdFatUtil::print_P(PGM_P str) {
|
||||||
for (uint8_t c; (c = pgm_read_byte(str)); str++) MYSERIAL.write(c);
|
for (uint8_t c; (c = pgm_read_byte(str)); str++) MYSERIAL.write(c);
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** %Print a string in flash memory followed by a CR/LF.
|
/**
|
||||||
|
* %Print a string in flash memory followed by a CR/LF.
|
||||||
*
|
*
|
||||||
* \param[in] pr Print object for output.
|
* \param[in] pr Print object for output.
|
||||||
* \param[in] str Pointer to string stored in flash memory.
|
* \param[in] str Pointer to string stored in flash memory.
|
||||||
*/
|
*/
|
||||||
void SdFatUtil::println_P(PGM_P str) {
|
void SdFatUtil::println_P(PGM_P str) { print_P(str); MYSERIAL.println(); }
|
||||||
print_P(str);
|
|
||||||
MYSERIAL.println();
|
/**
|
||||||
}
|
* %Print a string in flash memory to Serial.
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** %Print a string in flash memory to Serial.
|
|
||||||
*
|
*
|
||||||
* \param[in] str Pointer to string stored in flash memory.
|
* \param[in] str Pointer to string stored in flash memory.
|
||||||
*/
|
*/
|
||||||
void SdFatUtil::SerialPrint_P(PGM_P str) {
|
void SdFatUtil::SerialPrint_P(PGM_P str) { print_P(str); }
|
||||||
print_P(str);
|
|
||||||
}
|
/**
|
||||||
//------------------------------------------------------------------------------
|
* %Print a string in flash memory to Serial followed by a CR/LF.
|
||||||
/** %Print a string in flash memory to Serial followed by a CR/LF.
|
|
||||||
*
|
*
|
||||||
* \param[in] str Pointer to string stored in flash memory.
|
* \param[in] str Pointer to string stored in flash memory.
|
||||||
*/
|
*/
|
||||||
void SdFatUtil::SerialPrintln_P(PGM_P str) {
|
void SdFatUtil::SerialPrintln_P(PGM_P str) { println_P(str); }
|
||||||
println_P(str);
|
|
||||||
}
|
#endif // SDSUPPORT
|
||||||
#endif
|
|
||||||
|
|||||||
@@ -26,11 +26,8 @@
|
|||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#ifndef SdFatUtil_h
|
#ifndef _SDFATUTIL_H_
|
||||||
#define SdFatUtil_h
|
#define _SDFATUTIL_H_
|
||||||
|
|
||||||
#include "Marlin.h"
|
|
||||||
#if ENABLED(SDSUPPORT)
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* \file
|
* \file
|
||||||
@@ -51,6 +48,4 @@ namespace SdFatUtil {
|
|||||||
|
|
||||||
using namespace SdFatUtil; // NOLINT
|
using namespace SdFatUtil; // NOLINT
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // _SDFATUTIL_H_
|
||||||
|
|
||||||
#endif // SdFatUtil_h
|
|
||||||
|
|||||||
@@ -26,21 +26,24 @@
|
|||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#include "MarlinConfig.h"
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
#include "SdFile.h"
|
#include "SdFile.h"
|
||||||
/** Create a file object and open it in the current working directory.
|
|
||||||
|
/**
|
||||||
|
* Create a file object and open it in the current working directory.
|
||||||
*
|
*
|
||||||
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
|
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
|
||||||
*
|
*
|
||||||
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
|
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
|
||||||
* OR of open flags. see SdBaseFile::open(SdBaseFile*, const char*, uint8_t).
|
* OR of open flags. see SdBaseFile::open(SdBaseFile*, const char*, uint8_t).
|
||||||
*/
|
*/
|
||||||
SdFile::SdFile(const char* path, uint8_t oflag) : SdBaseFile(path, oflag) {
|
SdFile::SdFile(const char* path, uint8_t oflag) : SdBaseFile(path, oflag) { }
|
||||||
}
|
|
||||||
//------------------------------------------------------------------------------
|
/**
|
||||||
/** Write data to an open file.
|
* Write data to an open file.
|
||||||
*
|
*
|
||||||
* \note Data is moved to the cache but may not be written to the
|
* \note Data is moved to the cache but may not be written to the
|
||||||
* storage device until sync() is called.
|
* storage device until sync() is called.
|
||||||
@@ -55,41 +58,37 @@ SdFile::SdFile(const char* path, uint8_t oflag) : SdBaseFile(path, oflag) {
|
|||||||
* for a read-only file, device is full, a corrupt file system or an I/O error.
|
* for a read-only file, device is full, a corrupt file system or an I/O error.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
int16_t SdFile::write(const void* buf, uint16_t nbyte) {
|
int16_t SdFile::write(const void* buf, uint16_t nbyte) { return SdBaseFile::write(buf, nbyte); }
|
||||||
return SdBaseFile::write(buf, nbyte);
|
|
||||||
}
|
/**
|
||||||
//------------------------------------------------------------------------------
|
* Write a byte to a file. Required by the Arduino Print class.
|
||||||
/** Write a byte to a file. Required by the Arduino Print class.
|
|
||||||
* \param[in] b the byte to be written.
|
* \param[in] b the byte to be written.
|
||||||
* Use writeError to check for errors.
|
* Use writeError to check for errors.
|
||||||
*/
|
*/
|
||||||
#if ARDUINO >= 100
|
#if ARDUINO >= 100
|
||||||
size_t SdFile::write(uint8_t b) {
|
size_t SdFile::write(uint8_t b) { return SdBaseFile::write(&b, 1); }
|
||||||
return SdBaseFile::write(&b, 1);
|
|
||||||
}
|
|
||||||
#else
|
#else
|
||||||
void SdFile::write(uint8_t b) {
|
void SdFile::write(uint8_t b) { SdBaseFile::write(&b, 1); }
|
||||||
SdBaseFile::write(&b, 1);
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Write a string to a file. Used by the Arduino Print class.
|
/**
|
||||||
|
* Write a string to a file. Used by the Arduino Print class.
|
||||||
* \param[in] str Pointer to the string.
|
* \param[in] str Pointer to the string.
|
||||||
* Use writeError to check for errors.
|
* Use writeError to check for errors.
|
||||||
*/
|
*/
|
||||||
void SdFile::write(const char* str) {
|
void SdFile::write(const char* str) { SdBaseFile::write(str, strlen(str)); }
|
||||||
SdBaseFile::write(str, strlen(str));
|
|
||||||
}
|
/**
|
||||||
//------------------------------------------------------------------------------
|
* Write a PROGMEM string to a file.
|
||||||
/** Write a PROGMEM string to a file.
|
|
||||||
* \param[in] str Pointer to the PROGMEM string.
|
* \param[in] str Pointer to the PROGMEM string.
|
||||||
* Use writeError to check for errors.
|
* Use writeError to check for errors.
|
||||||
*/
|
*/
|
||||||
void SdFile::write_P(PGM_P str) {
|
void SdFile::write_P(PGM_P str) {
|
||||||
for (uint8_t c; (c = pgm_read_byte(str)); str++) write(c);
|
for (uint8_t c; (c = pgm_read_byte(str)); str++) write(c);
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Write a PROGMEM string followed by CR/LF to a file.
|
/**
|
||||||
|
* Write a PROGMEM string followed by CR/LF to a file.
|
||||||
* \param[in] str Pointer to the PROGMEM string.
|
* \param[in] str Pointer to the PROGMEM string.
|
||||||
* Use writeError to check for errors.
|
* Use writeError to check for errors.
|
||||||
*/
|
*/
|
||||||
@@ -98,5 +97,4 @@ void SdFile::writeln_P(PGM_P str) {
|
|||||||
write_P(PSTR("\r\n"));
|
write_P(PSTR("\r\n"));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // SDSUPPORT
|
||||||
#endif
|
|
||||||
|
|||||||
@@ -20,24 +20,23 @@
|
|||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \file
|
||||||
|
* \brief SdFile class
|
||||||
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Arduino SdFat Library
|
* Arduino SdFat Library
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Copyright (C) 2009 by William Greiman
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
/**
|
#ifndef _SDFILE_H_
|
||||||
* \file
|
#define _SDFILE_H_
|
||||||
* \brief SdFile class
|
|
||||||
*/
|
|
||||||
#include "Marlin.h"
|
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
|
||||||
#include "SdBaseFile.h"
|
#include "SdBaseFile.h"
|
||||||
#include <Print.h>
|
#include <Print.h>
|
||||||
#ifndef SdFile_h
|
|
||||||
#define SdFile_h
|
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* \class SdFile
|
* \class SdFile
|
||||||
* \brief SdBaseFile with Print.
|
* \brief SdBaseFile with Print.
|
||||||
@@ -57,7 +56,5 @@ class SdFile : public SdBaseFile, public Print {
|
|||||||
void write_P(PGM_P str);
|
void write_P(PGM_P str);
|
||||||
void writeln_P(PGM_P str);
|
void writeln_P(PGM_P str);
|
||||||
};
|
};
|
||||||
#endif // SdFile_h
|
|
||||||
|
|
||||||
|
#endif // _SDFILE_H_
|
||||||
#endif
|
|
||||||
|
|||||||
@@ -26,12 +26,11 @@
|
|||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#ifndef _SDINFO_H_
|
||||||
#if ENABLED(SDSUPPORT)
|
#define _SDINFO_H_
|
||||||
|
|
||||||
#ifndef SdInfo_h
|
|
||||||
#define SdInfo_h
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
// Based on the document:
|
// Based on the document:
|
||||||
//
|
//
|
||||||
// SD Specifications
|
// SD Specifications
|
||||||
@@ -42,46 +41,26 @@
|
|||||||
// May 18, 2010
|
// May 18, 2010
|
||||||
//
|
//
|
||||||
// http://www.sdcard.org/developers/tech/sdcard/pls/simplified_specs
|
// http://www.sdcard.org/developers/tech/sdcard/pls/simplified_specs
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// SD card commands
|
// SD card commands
|
||||||
/** GO_IDLE_STATE - init card in spi mode if CS low */
|
uint8_t const CMD0 = 0x00, // GO_IDLE_STATE - init card in spi mode if CS low
|
||||||
uint8_t const CMD0 = 0x00;
|
CMD8 = 0x08, // SEND_IF_COND - verify SD Memory Card interface operating condition
|
||||||
/** SEND_IF_COND - verify SD Memory Card interface operating condition.*/
|
CMD9 = 0x09, // SEND_CSD - read the Card Specific Data (CSD register)
|
||||||
uint8_t const CMD8 = 0x08;
|
CMD10 = 0x0A, // SEND_CID - read the card identification information (CID register)
|
||||||
/** SEND_CSD - read the Card Specific Data (CSD register) */
|
CMD12 = 0x0C, // STOP_TRANSMISSION - end multiple block read sequence
|
||||||
uint8_t const CMD9 = 0x09;
|
CMD13 = 0x0D, // SEND_STATUS - read the card status register
|
||||||
/** SEND_CID - read the card identification information (CID register) */
|
CMD17 = 0x11, // READ_SINGLE_BLOCK - read a single data block from the card
|
||||||
uint8_t const CMD10 = 0x0A;
|
CMD18 = 0x12, // READ_MULTIPLE_BLOCK - read a multiple data blocks from the card
|
||||||
/** STOP_TRANSMISSION - end multiple block read sequence */
|
CMD24 = 0x18, // WRITE_BLOCK - write a single data block to the card
|
||||||
uint8_t const CMD12 = 0x0C;
|
CMD25 = 0x19, // WRITE_MULTIPLE_BLOCK - write blocks of data until a STOP_TRANSMISSION
|
||||||
/** SEND_STATUS - read the card status register */
|
CMD32 = 0x20, // ERASE_WR_BLK_START - sets the address of the first block to be erased
|
||||||
uint8_t const CMD13 = 0x0D;
|
CMD33 = 0x21, // ERASE_WR_BLK_END - sets the address of the last block of the continuous range to be erased*/
|
||||||
/** READ_SINGLE_BLOCK - read a single data block from the card */
|
CMD38 = 0x26, // ERASE - erase all previously selected blocks */
|
||||||
uint8_t const CMD17 = 0x11;
|
CMD55 = 0x37, // APP_CMD - escape for application specific command */
|
||||||
/** READ_MULTIPLE_BLOCK - read a multiple data blocks from the card */
|
CMD58 = 0x3A, // READ_OCR - read the OCR register of a card */
|
||||||
uint8_t const CMD18 = 0x12;
|
ACMD23 = 0x17, // SET_WR_BLK_ERASE_COUNT - Set the number of write blocks to be pre-erased before writing */
|
||||||
/** WRITE_BLOCK - write a single data block to the card */
|
ACMD41 = 0x29; // SD_SEND_OP_COMD - Sends host capacity support information and activates the card's initialization process */
|
||||||
uint8_t const CMD24 = 0x18;
|
|
||||||
/** WRITE_MULTIPLE_BLOCK - write blocks of data until a STOP_TRANSMISSION */
|
|
||||||
uint8_t const CMD25 = 0x19;
|
|
||||||
/** ERASE_WR_BLK_START - sets the address of the first block to be erased */
|
|
||||||
uint8_t const CMD32 = 0x20;
|
|
||||||
/** ERASE_WR_BLK_END - sets the address of the last block of the continuous
|
|
||||||
range to be erased*/
|
|
||||||
uint8_t const CMD33 = 0x21;
|
|
||||||
/** ERASE - erase all previously selected blocks */
|
|
||||||
uint8_t const CMD38 = 0x26;
|
|
||||||
/** APP_CMD - escape for application specific command */
|
|
||||||
uint8_t const CMD55 = 0x37;
|
|
||||||
/** READ_OCR - read the OCR register of a card */
|
|
||||||
uint8_t const CMD58 = 0x3A;
|
|
||||||
/** SET_WR_BLK_ERASE_COUNT - Set the number of write blocks to be
|
|
||||||
pre-erased before writing */
|
|
||||||
uint8_t const ACMD23 = 0x17;
|
|
||||||
/** SD_SEND_OP_COMD - Sends host capacity support information and
|
|
||||||
activates the card's initialization process */
|
|
||||||
uint8_t const ACMD41 = 0x29;
|
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** status for card in the ready state */
|
/** status for card in the ready state */
|
||||||
uint8_t const R1_READY_STATE = 0x00;
|
uint8_t const R1_READY_STATE = 0x00;
|
||||||
/** status for card in the idle state */
|
/** status for card in the idle state */
|
||||||
@@ -98,7 +77,7 @@ uint8_t const WRITE_MULTIPLE_TOKEN = 0xFC;
|
|||||||
uint8_t const DATA_RES_MASK = 0x1F;
|
uint8_t const DATA_RES_MASK = 0x1F;
|
||||||
/** write data accepted token */
|
/** write data accepted token */
|
||||||
uint8_t const DATA_RES_ACCEPTED = 0x05;
|
uint8_t const DATA_RES_ACCEPTED = 0x05;
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Card IDentification (CID) register */
|
/** Card IDentification (CID) register */
|
||||||
typedef struct CID {
|
typedef struct CID {
|
||||||
// byte 0
|
// byte 0
|
||||||
@@ -134,7 +113,7 @@ typedef struct CID {
|
|||||||
/** CRC7 checksum */
|
/** CRC7 checksum */
|
||||||
unsigned char crc : 7;
|
unsigned char crc : 7;
|
||||||
} cid_t;
|
} cid_t;
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** CSD for version 1.00 cards */
|
/** CSD for version 1.00 cards */
|
||||||
typedef struct CSDV1 {
|
typedef struct CSDV1 {
|
||||||
// byte 0
|
// byte 0
|
||||||
@@ -196,7 +175,7 @@ typedef struct CSDV1 {
|
|||||||
unsigned char always1 : 1;
|
unsigned char always1 : 1;
|
||||||
unsigned char crc : 7;
|
unsigned char crc : 7;
|
||||||
} csd1_t;
|
} csd1_t;
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** CSD for version 2.00 cards */
|
/** CSD for version 2.00 cards */
|
||||||
typedef struct CSDV2 {
|
typedef struct CSDV2 {
|
||||||
// byte 0
|
// byte 0
|
||||||
@@ -278,12 +257,11 @@ typedef struct CSDV2 {
|
|||||||
/** checksum */
|
/** checksum */
|
||||||
unsigned char crc : 7;
|
unsigned char crc : 7;
|
||||||
} csd2_t;
|
} csd2_t;
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** union of old and new style CSD register */
|
/** union of old and new style CSD register */
|
||||||
union csd_t {
|
union csd_t {
|
||||||
csd1_t v1;
|
csd1_t v1;
|
||||||
csd2_t v2;
|
csd2_t v2;
|
||||||
};
|
};
|
||||||
#endif // SdInfo_h
|
|
||||||
|
|
||||||
#endif
|
#endif // _SDINFO_H_
|
||||||
|
|||||||
@@ -26,11 +26,12 @@
|
|||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#include "MarlinConfig.h"
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
#include "SdVolume.h"
|
#include "SdVolume.h"
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
#if !USE_MULTIPLE_CARDS
|
#if !USE_MULTIPLE_CARDS
|
||||||
// raw block cache
|
// raw block cache
|
||||||
uint32_t SdVolume::cacheBlockNumber_; // current block number
|
uint32_t SdVolume::cacheBlockNumber_; // current block number
|
||||||
@@ -39,7 +40,7 @@
|
|||||||
bool SdVolume::cacheDirty_; // cacheFlush() will write block if true
|
bool SdVolume::cacheDirty_; // cacheFlush() will write block if true
|
||||||
uint32_t SdVolume::cacheMirrorBlock_; // mirror block for second FAT
|
uint32_t SdVolume::cacheMirrorBlock_; // mirror block for second FAT
|
||||||
#endif // USE_MULTIPLE_CARDS
|
#endif // USE_MULTIPLE_CARDS
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// find a contiguous group of clusters
|
// find a contiguous group of clusters
|
||||||
bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
|
bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
|
||||||
// start of group
|
// start of group
|
||||||
@@ -73,14 +74,14 @@ bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
|
|||||||
// search the FAT for free clusters
|
// search the FAT for free clusters
|
||||||
for (uint32_t n = 0;; n++, endCluster++) {
|
for (uint32_t n = 0;; n++, endCluster++) {
|
||||||
// can't find space checked all clusters
|
// can't find space checked all clusters
|
||||||
if (n >= clusterCount_) goto FAIL;
|
if (n >= clusterCount_) return false;
|
||||||
|
|
||||||
// past end - start from beginning of FAT
|
// past end - start from beginning of FAT
|
||||||
if (endCluster > fatEnd) {
|
if (endCluster > fatEnd) {
|
||||||
bgnCluster = endCluster = 2;
|
bgnCluster = endCluster = 2;
|
||||||
}
|
}
|
||||||
uint32_t f;
|
uint32_t f;
|
||||||
if (!fatGet(endCluster, &f)) goto FAIL;
|
if (!fatGet(endCluster, &f)) return false;
|
||||||
|
|
||||||
if (f != 0) {
|
if (f != 0) {
|
||||||
// cluster in use try next cluster as bgnCluster
|
// cluster in use try next cluster as bgnCluster
|
||||||
@@ -92,16 +93,16 @@ bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
// mark end of chain
|
// mark end of chain
|
||||||
if (!fatPutEOC(endCluster)) goto FAIL;
|
if (!fatPutEOC(endCluster)) return false;
|
||||||
|
|
||||||
// link clusters
|
// link clusters
|
||||||
while (endCluster > bgnCluster) {
|
while (endCluster > bgnCluster) {
|
||||||
if (!fatPut(endCluster - 1, endCluster)) goto FAIL;
|
if (!fatPut(endCluster - 1, endCluster)) return false;
|
||||||
endCluster--;
|
endCluster--;
|
||||||
}
|
}
|
||||||
if (*curCluster != 0) {
|
if (*curCluster != 0) {
|
||||||
// connect chains
|
// connect chains
|
||||||
if (!fatPut(*curCluster, bgnCluster)) goto FAIL;
|
if (!fatPut(*curCluster, bgnCluster)) return false;
|
||||||
}
|
}
|
||||||
// return first cluster number to caller
|
// return first cluster number to caller
|
||||||
*curCluster = bgnCluster;
|
*curCluster = bgnCluster;
|
||||||
@@ -110,111 +111,94 @@ bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
|
|||||||
if (setStart) allocSearchStart_ = bgnCluster + 1;
|
if (setStart) allocSearchStart_ = bgnCluster + 1;
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
FAIL:
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
bool SdVolume::cacheFlush() {
|
bool SdVolume::cacheFlush() {
|
||||||
if (cacheDirty_) {
|
if (cacheDirty_) {
|
||||||
if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data)) {
|
if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data))
|
||||||
goto FAIL;
|
return false;
|
||||||
}
|
|
||||||
// mirror FAT tables
|
// mirror FAT tables
|
||||||
if (cacheMirrorBlock_) {
|
if (cacheMirrorBlock_) {
|
||||||
if (!sdCard_->writeBlock(cacheMirrorBlock_, cacheBuffer_.data)) {
|
if (!sdCard_->writeBlock(cacheMirrorBlock_, cacheBuffer_.data))
|
||||||
goto FAIL;
|
return false;
|
||||||
}
|
|
||||||
cacheMirrorBlock_ = 0;
|
cacheMirrorBlock_ = 0;
|
||||||
}
|
}
|
||||||
cacheDirty_ = 0;
|
cacheDirty_ = 0;
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
FAIL:
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
bool SdVolume::cacheRawBlock(uint32_t blockNumber, bool dirty) {
|
bool SdVolume::cacheRawBlock(uint32_t blockNumber, bool dirty) {
|
||||||
if (cacheBlockNumber_ != blockNumber) {
|
if (cacheBlockNumber_ != blockNumber) {
|
||||||
if (!cacheFlush()) goto FAIL;
|
if (!cacheFlush()) return false;
|
||||||
if (!sdCard_->readBlock(blockNumber, cacheBuffer_.data)) goto FAIL;
|
if (!sdCard_->readBlock(blockNumber, cacheBuffer_.data)) return false;
|
||||||
cacheBlockNumber_ = blockNumber;
|
cacheBlockNumber_ = blockNumber;
|
||||||
}
|
}
|
||||||
if (dirty) cacheDirty_ = true;
|
if (dirty) cacheDirty_ = true;
|
||||||
return true;
|
return true;
|
||||||
FAIL:
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// return the size in bytes of a cluster chain
|
// return the size in bytes of a cluster chain
|
||||||
bool SdVolume::chainSize(uint32_t cluster, uint32_t* size) {
|
bool SdVolume::chainSize(uint32_t cluster, uint32_t* size) {
|
||||||
uint32_t s = 0;
|
uint32_t s = 0;
|
||||||
do {
|
do {
|
||||||
if (!fatGet(cluster, &cluster)) goto FAIL;
|
if (!fatGet(cluster, &cluster)) return false;
|
||||||
s += 512UL << clusterSizeShift_;
|
s += 512UL << clusterSizeShift_;
|
||||||
} while (!isEOC(cluster));
|
} while (!isEOC(cluster));
|
||||||
*size = s;
|
*size = s;
|
||||||
return true;
|
return true;
|
||||||
FAIL:
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// Fetch a FAT entry
|
// Fetch a FAT entry
|
||||||
bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) {
|
bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) {
|
||||||
uint32_t lba;
|
uint32_t lba;
|
||||||
if (cluster > (clusterCount_ + 1)) goto FAIL;
|
if (cluster > (clusterCount_ + 1)) return false;
|
||||||
if (FAT12_SUPPORT && fatType_ == 12) {
|
if (FAT12_SUPPORT && fatType_ == 12) {
|
||||||
uint16_t index = cluster;
|
uint16_t index = cluster;
|
||||||
index += index >> 1;
|
index += index >> 1;
|
||||||
lba = fatStartBlock_ + (index >> 9);
|
lba = fatStartBlock_ + (index >> 9);
|
||||||
if (!cacheRawBlock(lba, CACHE_FOR_READ)) goto FAIL;
|
if (!cacheRawBlock(lba, CACHE_FOR_READ)) return false;
|
||||||
index &= 0x1FF;
|
index &= 0x1FF;
|
||||||
uint16_t tmp = cacheBuffer_.data[index];
|
uint16_t tmp = cacheBuffer_.data[index];
|
||||||
index++;
|
index++;
|
||||||
if (index == 512) {
|
if (index == 512) {
|
||||||
if (!cacheRawBlock(lba + 1, CACHE_FOR_READ)) goto FAIL;
|
if (!cacheRawBlock(lba + 1, CACHE_FOR_READ)) return false;
|
||||||
index = 0;
|
index = 0;
|
||||||
}
|
}
|
||||||
tmp |= cacheBuffer_.data[index] << 8;
|
tmp |= cacheBuffer_.data[index] << 8;
|
||||||
*value = cluster & 1 ? tmp >> 4 : tmp & 0xFFF;
|
*value = cluster & 1 ? tmp >> 4 : tmp & 0xFFF;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
if (fatType_ == 16) {
|
|
||||||
|
if (fatType_ == 16)
|
||||||
lba = fatStartBlock_ + (cluster >> 8);
|
lba = fatStartBlock_ + (cluster >> 8);
|
||||||
}
|
else if (fatType_ == 32)
|
||||||
else if (fatType_ == 32) {
|
|
||||||
lba = fatStartBlock_ + (cluster >> 7);
|
lba = fatStartBlock_ + (cluster >> 7);
|
||||||
}
|
else
|
||||||
else {
|
|
||||||
goto FAIL;
|
|
||||||
}
|
|
||||||
if (lba != cacheBlockNumber_) {
|
|
||||||
if (!cacheRawBlock(lba, CACHE_FOR_READ)) goto FAIL;
|
|
||||||
}
|
|
||||||
if (fatType_ == 16) {
|
|
||||||
*value = cacheBuffer_.fat16[cluster & 0xFF];
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
*value = cacheBuffer_.fat32[cluster & 0x7F] & FAT32MASK;
|
|
||||||
}
|
|
||||||
return true;
|
|
||||||
FAIL:
|
|
||||||
return false;
|
return false;
|
||||||
|
|
||||||
|
if (lba != cacheBlockNumber_ && !cacheRawBlock(lba, CACHE_FOR_READ))
|
||||||
|
return false;
|
||||||
|
|
||||||
|
*value = (fatType_ == 16) ? cacheBuffer_.fat16[cluster & 0xFF] : (cacheBuffer_.fat32[cluster & 0x7F] & FAT32MASK);
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// Store a FAT entry
|
// Store a FAT entry
|
||||||
bool SdVolume::fatPut(uint32_t cluster, uint32_t value) {
|
bool SdVolume::fatPut(uint32_t cluster, uint32_t value) {
|
||||||
uint32_t lba;
|
uint32_t lba;
|
||||||
// error if reserved cluster
|
// error if reserved cluster
|
||||||
if (cluster < 2) goto FAIL;
|
if (cluster < 2) return false;
|
||||||
|
|
||||||
// error if not in FAT
|
// error if not in FAT
|
||||||
if (cluster > (clusterCount_ + 1)) goto FAIL;
|
if (cluster > (clusterCount_ + 1)) return false;
|
||||||
|
|
||||||
if (FAT12_SUPPORT && fatType_ == 12) {
|
if (FAT12_SUPPORT && fatType_ == 12) {
|
||||||
uint16_t index = cluster;
|
uint16_t index = cluster;
|
||||||
index += index >> 1;
|
index += index >> 1;
|
||||||
lba = fatStartBlock_ + (index >> 9);
|
lba = fatStartBlock_ + (index >> 9);
|
||||||
if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto FAIL;
|
if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) return false;
|
||||||
// mirror second FAT
|
// mirror second FAT
|
||||||
if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
|
if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
|
||||||
index &= 0x1FF;
|
index &= 0x1FF;
|
||||||
@@ -227,7 +211,7 @@ bool SdVolume::fatPut(uint32_t cluster, uint32_t value) {
|
|||||||
if (index == 512) {
|
if (index == 512) {
|
||||||
lba++;
|
lba++;
|
||||||
index = 0;
|
index = 0;
|
||||||
if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto FAIL;
|
if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) return false;
|
||||||
// mirror second FAT
|
// mirror second FAT
|
||||||
if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
|
if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
|
||||||
}
|
}
|
||||||
@@ -238,51 +222,45 @@ bool SdVolume::fatPut(uint32_t cluster, uint32_t value) {
|
|||||||
cacheBuffer_.data[index] = tmp;
|
cacheBuffer_.data[index] = tmp;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
if (fatType_ == 16) {
|
|
||||||
|
if (fatType_ == 16)
|
||||||
lba = fatStartBlock_ + (cluster >> 8);
|
lba = fatStartBlock_ + (cluster >> 8);
|
||||||
}
|
else if (fatType_ == 32)
|
||||||
else if (fatType_ == 32) {
|
|
||||||
lba = fatStartBlock_ + (cluster >> 7);
|
lba = fatStartBlock_ + (cluster >> 7);
|
||||||
}
|
else
|
||||||
else {
|
return false;
|
||||||
goto FAIL;
|
|
||||||
}
|
if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) return false;
|
||||||
if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto FAIL;
|
|
||||||
// store entry
|
// store entry
|
||||||
if (fatType_ == 16) {
|
if (fatType_ == 16)
|
||||||
cacheBuffer_.fat16[cluster & 0xFF] = value;
|
cacheBuffer_.fat16[cluster & 0xFF] = value;
|
||||||
}
|
else
|
||||||
else {
|
|
||||||
cacheBuffer_.fat32[cluster & 0x7F] = value;
|
cacheBuffer_.fat32[cluster & 0x7F] = value;
|
||||||
}
|
|
||||||
// mirror second FAT
|
// mirror second FAT
|
||||||
if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
|
if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_;
|
||||||
return true;
|
return true;
|
||||||
FAIL:
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// free a cluster chain
|
// free a cluster chain
|
||||||
bool SdVolume::freeChain(uint32_t cluster) {
|
bool SdVolume::freeChain(uint32_t cluster) {
|
||||||
uint32_t next;
|
|
||||||
|
|
||||||
// clear free cluster location
|
// clear free cluster location
|
||||||
allocSearchStart_ = 2;
|
allocSearchStart_ = 2;
|
||||||
|
|
||||||
do {
|
do {
|
||||||
if (!fatGet(cluster, &next)) goto FAIL;
|
uint32_t next;
|
||||||
|
if (!fatGet(cluster, &next)) return false;
|
||||||
|
|
||||||
// free cluster
|
// free cluster
|
||||||
if (!fatPut(cluster, 0)) goto FAIL;
|
if (!fatPut(cluster, 0)) return false;
|
||||||
|
|
||||||
cluster = next;
|
cluster = next;
|
||||||
} while (!isEOC(cluster));
|
} while (!isEOC(cluster));
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
FAIL:
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Volume free space in clusters.
|
/** Volume free space in clusters.
|
||||||
*
|
*
|
||||||
* \return Count of free clusters for success or -1 if an error occurs.
|
* \return Count of free clusters for success or -1 if an error occurs.
|
||||||
@@ -292,34 +270,28 @@ int32_t SdVolume::freeClusterCount() {
|
|||||||
uint16_t n;
|
uint16_t n;
|
||||||
uint32_t todo = clusterCount_ + 2;
|
uint32_t todo = clusterCount_ + 2;
|
||||||
|
|
||||||
if (fatType_ == 16) {
|
if (fatType_ == 16)
|
||||||
n = 256;
|
n = 256;
|
||||||
}
|
else if (fatType_ == 32)
|
||||||
else if (fatType_ == 32) {
|
|
||||||
n = 128;
|
n = 128;
|
||||||
}
|
else // put FAT12 here
|
||||||
else {
|
|
||||||
// put FAT12 here
|
|
||||||
return -1;
|
return -1;
|
||||||
}
|
|
||||||
|
|
||||||
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;
|
||||||
NOMORE(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++;
|
||||||
}
|
}
|
||||||
}
|
|
||||||
else {
|
else {
|
||||||
for (uint16_t i = 0; i < n; i++) {
|
for (uint16_t i = 0; i < n; i++)
|
||||||
if (cacheBuffer_.fat32[i] == 0) free++;
|
if (cacheBuffer_.fat32[i] == 0) free++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
|
||||||
return free;
|
return free;
|
||||||
}
|
}
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/** Initialize a FAT volume.
|
/** Initialize a FAT volume.
|
||||||
*
|
*
|
||||||
* \param[in] dev The SD card where the volume is located.
|
* \param[in] dev The SD card where the volume is located.
|
||||||
@@ -329,14 +301,12 @@ int32_t SdVolume::freeClusterCount() {
|
|||||||
* a MBR, Master Boot Record, or zero if the device is formatted as
|
* a MBR, Master Boot Record, or zero if the device is formatted as
|
||||||
* a super floppy with the FAT boot sector in block zero.
|
* a super floppy with the FAT boot sector in block zero.
|
||||||
*
|
*
|
||||||
* \return The value one, true, is returned for success and
|
* \return true for success, false for failure.
|
||||||
* the value zero, false, is returned for failure. Reasons for
|
* Reasons for failure include not finding a valid partition, not finding a valid
|
||||||
* failure include not finding a valid partition, not finding a valid
|
|
||||||
* FAT file system in the specified partition or an I/O error.
|
* FAT file system in the specified partition or an I/O error.
|
||||||
*/
|
*/
|
||||||
bool SdVolume::init(Sd2Card* dev, uint8_t part) {
|
bool SdVolume::init(Sd2Card* dev, uint8_t part) {
|
||||||
uint32_t totalBlocks;
|
uint32_t totalBlocks, volumeStartBlock = 0;
|
||||||
uint32_t volumeStartBlock = 0;
|
|
||||||
fat32_boot_t* fbs;
|
fat32_boot_t* fbs;
|
||||||
|
|
||||||
sdCard_ = dev;
|
sdCard_ = dev;
|
||||||
@@ -349,25 +319,21 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
|
|||||||
// if part == 0 assume super floppy with FAT boot sector in block zero
|
// if part == 0 assume super floppy with FAT boot sector in block zero
|
||||||
// if part > 0 assume mbr volume with partition table
|
// if part > 0 assume mbr volume with partition table
|
||||||
if (part) {
|
if (part) {
|
||||||
if (part > 4)goto FAIL;
|
if (part > 4) return false;
|
||||||
if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto FAIL;
|
if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) return false;
|
||||||
part_t* p = &cacheBuffer_.mbr.part[part - 1];
|
part_t* p = &cacheBuffer_.mbr.part[part - 1];
|
||||||
if ((p->boot & 0x7F) != 0 ||
|
if ((p->boot & 0x7F) != 0 || p->totalSectors < 100 || p->firstSector == 0)
|
||||||
p->totalSectors < 100 ||
|
return false; // not a valid partition
|
||||||
p->firstSector == 0) {
|
|
||||||
// not a valid partition
|
|
||||||
goto FAIL;
|
|
||||||
}
|
|
||||||
volumeStartBlock = p->firstSector;
|
volumeStartBlock = p->firstSector;
|
||||||
}
|
}
|
||||||
if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto FAIL;
|
if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) return false;
|
||||||
fbs = &cacheBuffer_.fbs32;
|
fbs = &cacheBuffer_.fbs32;
|
||||||
if (fbs->bytesPerSector != 512 ||
|
if (fbs->bytesPerSector != 512 ||
|
||||||
fbs->fatCount == 0 ||
|
fbs->fatCount == 0 ||
|
||||||
fbs->reservedSectorCount == 0 ||
|
fbs->reservedSectorCount == 0 ||
|
||||||
fbs->sectorsPerCluster == 0) {
|
fbs->sectorsPerCluster == 0) {
|
||||||
// not valid FAT volume
|
// not valid FAT volume
|
||||||
goto FAIL;
|
return false;
|
||||||
}
|
}
|
||||||
fatCount_ = fbs->fatCount;
|
fatCount_ = fbs->fatCount;
|
||||||
blocksPerCluster_ = fbs->sectorsPerCluster;
|
blocksPerCluster_ = fbs->sectorsPerCluster;
|
||||||
@@ -375,7 +341,7 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
|
|||||||
clusterSizeShift_ = 0;
|
clusterSizeShift_ = 0;
|
||||||
while (blocksPerCluster_ != _BV(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) return false;
|
||||||
}
|
}
|
||||||
blocksPerFat_ = fbs->sectorsPerFat16 ?
|
blocksPerFat_ = fbs->sectorsPerFat16 ?
|
||||||
fbs->sectorsPerFat16 : fbs->sectorsPerFat32;
|
fbs->sectorsPerFat16 : fbs->sectorsPerFat32;
|
||||||
@@ -404,17 +370,15 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) {
|
|||||||
// FAT type is determined by cluster count
|
// FAT type is determined by cluster count
|
||||||
if (clusterCount_ < 4085) {
|
if (clusterCount_ < 4085) {
|
||||||
fatType_ = 12;
|
fatType_ = 12;
|
||||||
if (!FAT12_SUPPORT) goto FAIL;
|
if (!FAT12_SUPPORT) return false;
|
||||||
}
|
}
|
||||||
else if (clusterCount_ < 65525) {
|
else if (clusterCount_ < 65525)
|
||||||
fatType_ = 16;
|
fatType_ = 16;
|
||||||
}
|
|
||||||
else {
|
else {
|
||||||
rootDirStart_ = fbs->fat32RootCluster;
|
rootDirStart_ = fbs->fat32RootCluster;
|
||||||
fatType_ = 32;
|
fatType_ = 32;
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
FAIL:
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
#endif // SDSUPPORT
|
||||||
|
|||||||
@@ -20,20 +20,20 @@
|
|||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* \file
|
||||||
|
* \brief SdVolume class
|
||||||
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Arduino SdFat Library
|
* Arduino SdFat Library
|
||||||
* Copyright (C) 2009 by William Greiman
|
* Copyright (C) 2009 by William Greiman
|
||||||
*
|
*
|
||||||
* This file is part of the Arduino Sd2Card Library
|
* This file is part of the Arduino Sd2Card Library
|
||||||
*/
|
*/
|
||||||
#include "Marlin.h"
|
#ifndef _SDVOLUME_H_
|
||||||
#if ENABLED(SDSUPPORT)
|
#define _SDVOLUME_H_
|
||||||
#ifndef SdVolume_h
|
|
||||||
#define SdVolume_h
|
|
||||||
/**
|
|
||||||
* \file
|
|
||||||
* \brief SdVolume class
|
|
||||||
*/
|
|
||||||
#include "SdFatConfig.h"
|
#include "SdFatConfig.h"
|
||||||
#include "Sd2Card.h"
|
#include "Sd2Card.h"
|
||||||
#include "SdFatStructs.h"
|
#include "SdFatStructs.h"
|
||||||
@@ -44,33 +44,26 @@
|
|||||||
* \brief Cache for an SD data block
|
* \brief Cache for an SD data block
|
||||||
*/
|
*/
|
||||||
union cache_t {
|
union cache_t {
|
||||||
/** Used to access cached file data blocks. */
|
uint8_t data[512]; // Used to access cached file data blocks.
|
||||||
uint8_t data[512];
|
uint16_t fat16[256]; // Used to access cached FAT16 entries.
|
||||||
/** Used to access cached FAT16 entries. */
|
uint32_t fat32[128]; // Used to access cached FAT32 entries.
|
||||||
uint16_t fat16[256];
|
dir_t dir[16]; // Used to access cached directory entries.
|
||||||
/** Used to access cached FAT32 entries. */
|
mbr_t mbr; // Used to access a cached Master Boot Record.
|
||||||
uint32_t fat32[128];
|
fat_boot_t fbs; // Used to access to a cached FAT boot sector.
|
||||||
/** Used to access cached directory entries. */
|
fat32_boot_t fbs32; // Used to access to a cached FAT32 boot sector.
|
||||||
dir_t dir[16];
|
fat32_fsinfo_t fsinfo; // Used to access to a cached FAT32 FSINFO sector.
|
||||||
/** Used to access a cached Master Boot Record. */
|
|
||||||
mbr_t mbr;
|
|
||||||
/** Used to access to a cached FAT boot sector. */
|
|
||||||
fat_boot_t fbs;
|
|
||||||
/** Used to access to a cached FAT32 boot sector. */
|
|
||||||
fat32_boot_t fbs32;
|
|
||||||
/** Used to access to a cached FAT32 FSINFO sector. */
|
|
||||||
fat32_fsinfo_t fsinfo;
|
|
||||||
};
|
};
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
/**
|
/**
|
||||||
* \class SdVolume
|
* \class SdVolume
|
||||||
* \brief Access FAT16 and FAT32 volumes on SD and SDHC cards.
|
* \brief Access FAT16 and FAT32 volumes on SD and SDHC cards.
|
||||||
*/
|
*/
|
||||||
class SdVolume {
|
class SdVolume {
|
||||||
public:
|
public:
|
||||||
/** Create an instance of SdVolume */
|
// Create an instance of SdVolume
|
||||||
SdVolume() : fatType_(0) {}
|
SdVolume() : fatType_(0) {}
|
||||||
/** Clear the cache and returns a pointer to the cache. Used by the WaveRP
|
/**
|
||||||
|
* Clear the cache and returns a pointer to the cache. Used by the WaveRP
|
||||||
* recorder to do raw write to the SD card. Not for normal apps.
|
* recorder to do raw write to the SD card. Not for normal apps.
|
||||||
* \return A pointer to the cache buffer or zero if an error occurs.
|
* \return A pointer to the cache buffer or zero if an error occurs.
|
||||||
*/
|
*/
|
||||||
@@ -79,54 +72,53 @@ class SdVolume {
|
|||||||
cacheBlockNumber_ = 0xFFFFFFFF;
|
cacheBlockNumber_ = 0xFFFFFFFF;
|
||||||
return &cacheBuffer_;
|
return &cacheBuffer_;
|
||||||
}
|
}
|
||||||
/** Initialize a FAT volume. Try partition one first then try super
|
|
||||||
|
/**
|
||||||
|
* Initialize a FAT volume. Try partition one first then try super
|
||||||
* floppy format.
|
* floppy format.
|
||||||
*
|
*
|
||||||
* \param[in] dev The Sd2Card where the volume is located.
|
* \param[in] dev The Sd2Card where the volume is located.
|
||||||
*
|
*
|
||||||
* \return The value one, true, is returned for success and
|
* \return true for success, false for failure.
|
||||||
* the value zero, false, is returned for failure. Reasons for
|
* Reasons for failure include not finding a valid partition, not finding
|
||||||
* failure include not finding a valid partition, not finding a valid
|
* a valid FAT file system or an I/O error.
|
||||||
* FAT file system or an I/O error.
|
|
||||||
*/
|
*/
|
||||||
bool init(Sd2Card* dev) { return init(dev, 1) ? true : init(dev, 0);}
|
bool init(Sd2Card* dev) { return init(dev, 1) ? true : init(dev, 0); }
|
||||||
bool init(Sd2Card* dev, uint8_t part);
|
bool init(Sd2Card* dev, uint8_t part);
|
||||||
|
|
||||||
// inline functions that return volume info
|
// inline functions that return volume info
|
||||||
/** \return The volume's cluster size in blocks. */
|
uint8_t blocksPerCluster() const { return blocksPerCluster_; } //> \return The volume's cluster size in blocks.
|
||||||
uint8_t blocksPerCluster() const {return blocksPerCluster_;}
|
uint32_t blocksPerFat() const { return blocksPerFat_; } //> \return The number of blocks in one FAT.
|
||||||
/** \return The number of blocks in one FAT. */
|
uint32_t clusterCount() const { return clusterCount_; } //> \return The total number of clusters in the volume.
|
||||||
uint32_t blocksPerFat() const {return blocksPerFat_;}
|
uint8_t clusterSizeShift() const { return clusterSizeShift_; } //> \return The shift count required to multiply by blocksPerCluster.
|
||||||
/** \return The total number of clusters in the volume. */
|
uint32_t dataStartBlock() const { return dataStartBlock_; } //> \return The logical block number for the start of file data.
|
||||||
uint32_t clusterCount() const {return clusterCount_;}
|
uint8_t fatCount() const { return fatCount_; } //> \return The number of FAT structures on the volume.
|
||||||
/** \return The shift count required to multiply by blocksPerCluster. */
|
uint32_t fatStartBlock() const { return fatStartBlock_; } //> \return The logical block number for the start of the first FAT.
|
||||||
uint8_t clusterSizeShift() const {return clusterSizeShift_;}
|
uint8_t fatType() const { return fatType_; } //> \return The FAT type of the volume. Values are 12, 16 or 32.
|
||||||
/** \return The logical block number for the start of file data. */
|
|
||||||
uint32_t dataStartBlock() const {return dataStartBlock_;}
|
|
||||||
/** \return The number of FAT structures on the volume. */
|
|
||||||
uint8_t fatCount() const {return fatCount_;}
|
|
||||||
/** \return The logical block number for the start of the first FAT. */
|
|
||||||
uint32_t fatStartBlock() const {return fatStartBlock_;}
|
|
||||||
/** \return The FAT type of the volume. Values are 12, 16 or 32. */
|
|
||||||
uint8_t fatType() const {return fatType_;}
|
|
||||||
int32_t freeClusterCount();
|
int32_t freeClusterCount();
|
||||||
/** \return The number of entries in the root directory for FAT16 volumes. */
|
uint32_t rootDirEntryCount() const { return rootDirEntryCount_; } /** \return The number of entries in the root directory for FAT16 volumes. */
|
||||||
uint32_t rootDirEntryCount() const {return rootDirEntryCount_;}
|
|
||||||
/** \return The logical block number for the start of the root directory
|
/**
|
||||||
on FAT16 volumes or the first cluster number on FAT32 volumes. */
|
* \return The logical block number for the start of the root directory
|
||||||
uint32_t rootDirStart() const {return rootDirStart_;}
|
* on FAT16 volumes or the first cluster number on FAT32 volumes.
|
||||||
/** Sd2Card object for this volume
|
*/
|
||||||
|
uint32_t rootDirStart() const { return rootDirStart_; }
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Sd2Card object for this volume
|
||||||
* \return pointer to Sd2Card object.
|
* \return pointer to Sd2Card object.
|
||||||
*/
|
*/
|
||||||
Sd2Card* sdCard() {return sdCard_;}
|
Sd2Card* sdCard() { return sdCard_; }
|
||||||
/** Debug access to FAT table
|
|
||||||
|
/**
|
||||||
|
* Debug access to FAT table
|
||||||
*
|
*
|
||||||
* \param[in] n cluster number.
|
* \param[in] n cluster number.
|
||||||
* \param[out] v value of entry
|
* \param[out] v value of entry
|
||||||
* \return true for success or false for failure
|
* \return true for success or false for failure
|
||||||
*/
|
*/
|
||||||
bool dbgFat(uint32_t n, uint32_t* v) {return fatGet(n, v);}
|
bool dbgFat(uint32_t n, uint32_t* v) { return fatGet(n, v); }
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
private:
|
private:
|
||||||
// Allow SdBaseFile access to SdVolume private data.
|
// Allow SdBaseFile access to SdVolume private data.
|
||||||
friend class SdBaseFile;
|
friend class SdBaseFile;
|
||||||
@@ -136,19 +128,20 @@ class SdVolume {
|
|||||||
// value for dirty argument in cacheRawBlock to indicate write to cache
|
// value for dirty argument in cacheRawBlock to indicate write to cache
|
||||||
static bool const CACHE_FOR_WRITE = true;
|
static bool const CACHE_FOR_WRITE = true;
|
||||||
|
|
||||||
#if USE_MULTIPLE_CARDS
|
#if USE_MULTIPLE_CARDS
|
||||||
cache_t cacheBuffer_; // 512 byte cache for device blocks
|
cache_t cacheBuffer_; // 512 byte cache for device blocks
|
||||||
uint32_t cacheBlockNumber_; // Logical number of block in the cache
|
uint32_t cacheBlockNumber_; // Logical number of block in the cache
|
||||||
Sd2Card* sdCard_; // Sd2Card object for cache
|
Sd2Card* sdCard_; // Sd2Card object for cache
|
||||||
bool cacheDirty_; // cacheFlush() will write block if true
|
bool cacheDirty_; // cacheFlush() will write block if true
|
||||||
uint32_t cacheMirrorBlock_; // block number for mirror FAT
|
uint32_t cacheMirrorBlock_; // block number for mirror FAT
|
||||||
#else // USE_MULTIPLE_CARDS
|
#else
|
||||||
static cache_t cacheBuffer_; // 512 byte cache for device blocks
|
static cache_t cacheBuffer_; // 512 byte cache for device blocks
|
||||||
static uint32_t cacheBlockNumber_; // Logical number of block in the cache
|
static uint32_t cacheBlockNumber_; // Logical number of block in the cache
|
||||||
static Sd2Card* sdCard_; // Sd2Card object for cache
|
static Sd2Card* sdCard_; // Sd2Card object for cache
|
||||||
static bool cacheDirty_; // cacheFlush() will write block if true
|
static bool cacheDirty_; // cacheFlush() will write block if true
|
||||||
static uint32_t cacheMirrorBlock_; // block number for mirror FAT
|
static uint32_t cacheMirrorBlock_; // block number for mirror FAT
|
||||||
#endif // USE_MULTIPLE_CARDS
|
#endif
|
||||||
|
|
||||||
uint32_t allocSearchStart_; // start cluster for alloc search
|
uint32_t allocSearchStart_; // start cluster for alloc search
|
||||||
uint8_t blocksPerCluster_; // cluster size in blocks
|
uint8_t blocksPerCluster_; // cluster size in blocks
|
||||||
uint32_t blocksPerFat_; // FAT size in blocks
|
uint32_t blocksPerFat_; // FAT size in blocks
|
||||||
@@ -160,68 +153,59 @@ class SdVolume {
|
|||||||
uint8_t fatType_; // volume type (12, 16, OR 32)
|
uint8_t fatType_; // volume type (12, 16, OR 32)
|
||||||
uint16_t rootDirEntryCount_; // number of entries in FAT16 root dir
|
uint16_t rootDirEntryCount_; // number of entries in FAT16 root dir
|
||||||
uint32_t rootDirStart_; // root start block for FAT16, cluster for FAT32
|
uint32_t rootDirStart_; // root start block for FAT16, cluster for FAT32
|
||||||
//----------------------------------------------------------------------------
|
|
||||||
bool allocContiguous(uint32_t count, uint32_t* curCluster);
|
bool allocContiguous(uint32_t count, uint32_t* curCluster);
|
||||||
uint8_t blockOfCluster(uint32_t position) const {
|
uint8_t blockOfCluster(uint32_t position) const { return (position >> 9) & (blocksPerCluster_ - 1); }
|
||||||
return (position >> 9) & (blocksPerCluster_ - 1);
|
uint32_t clusterStartBlock(uint32_t cluster) const { return dataStartBlock_ + ((cluster - 2) << clusterSizeShift_); }
|
||||||
}
|
uint32_t blockNumber(uint32_t cluster, uint32_t position) const { return clusterStartBlock(cluster) + blockOfCluster(position); }
|
||||||
uint32_t clusterStartBlock(uint32_t cluster) const {
|
|
||||||
return dataStartBlock_ + ((cluster - 2) << clusterSizeShift_);
|
cache_t* cache() { return &cacheBuffer_; }
|
||||||
}
|
uint32_t cacheBlockNumber() const { return cacheBlockNumber_; }
|
||||||
uint32_t blockNumber(uint32_t cluster, uint32_t position) const {
|
|
||||||
return clusterStartBlock(cluster) + blockOfCluster(position);
|
#if USE_MULTIPLE_CARDS
|
||||||
}
|
|
||||||
cache_t* cache() {return &cacheBuffer_;}
|
|
||||||
uint32_t cacheBlockNumber() {return cacheBlockNumber_;}
|
|
||||||
#if USE_MULTIPLE_CARDS
|
|
||||||
bool cacheFlush();
|
bool cacheFlush();
|
||||||
bool cacheRawBlock(uint32_t blockNumber, bool dirty);
|
bool cacheRawBlock(uint32_t blockNumber, bool dirty);
|
||||||
#else // USE_MULTIPLE_CARDS
|
#else
|
||||||
static bool cacheFlush();
|
static bool cacheFlush();
|
||||||
static bool cacheRawBlock(uint32_t blockNumber, bool dirty);
|
static bool cacheRawBlock(uint32_t blockNumber, bool dirty);
|
||||||
#endif // USE_MULTIPLE_CARDS
|
#endif
|
||||||
|
|
||||||
// used by SdBaseFile write to assign cache to SD location
|
// used by SdBaseFile write to assign cache to SD location
|
||||||
void cacheSetBlockNumber(uint32_t blockNumber, bool dirty) {
|
void cacheSetBlockNumber(uint32_t blockNumber, bool dirty) {
|
||||||
cacheDirty_ = dirty;
|
cacheDirty_ = dirty;
|
||||||
cacheBlockNumber_ = blockNumber;
|
cacheBlockNumber_ = blockNumber;
|
||||||
}
|
}
|
||||||
void cacheSetDirty() {cacheDirty_ |= CACHE_FOR_WRITE;}
|
void cacheSetDirty() { cacheDirty_ |= CACHE_FOR_WRITE; }
|
||||||
bool chainSize(uint32_t beginCluster, uint32_t* size);
|
bool chainSize(uint32_t beginCluster, uint32_t* size);
|
||||||
bool fatGet(uint32_t cluster, uint32_t* value);
|
bool fatGet(uint32_t cluster, uint32_t* value);
|
||||||
bool fatPut(uint32_t cluster, uint32_t value);
|
bool fatPut(uint32_t cluster, uint32_t value);
|
||||||
bool fatPutEOC(uint32_t cluster) {
|
bool fatPutEOC(uint32_t cluster) { return fatPut(cluster, 0x0FFFFFFF); }
|
||||||
return fatPut(cluster, 0x0FFFFFFF);
|
|
||||||
}
|
|
||||||
bool freeChain(uint32_t cluster);
|
bool freeChain(uint32_t cluster);
|
||||||
bool isEOC(uint32_t cluster) const {
|
bool isEOC(uint32_t cluster) const {
|
||||||
if (FAT12_SUPPORT && fatType_ == 12) return cluster >= FAT12EOC_MIN;
|
if (FAT12_SUPPORT && fatType_ == 12) return cluster >= FAT12EOC_MIN;
|
||||||
if (fatType_ == 16) return cluster >= FAT16EOC_MIN;
|
if (fatType_ == 16) return cluster >= FAT16EOC_MIN;
|
||||||
return cluster >= FAT32EOC_MIN;
|
return cluster >= FAT32EOC_MIN;
|
||||||
}
|
}
|
||||||
bool readBlock(uint32_t block, uint8_t* dst) {
|
bool readBlock(uint32_t block, uint8_t* dst) { return sdCard_->readBlock(block, dst); }
|
||||||
return sdCard_->readBlock(block, dst);
|
bool writeBlock(uint32_t block, const uint8_t* dst) { return sdCard_->writeBlock(block, dst); }
|
||||||
}
|
|
||||||
bool writeBlock(uint32_t block, const uint8_t* dst) {
|
// Deprecated functions
|
||||||
return sdCard_->writeBlock(block, dst);
|
#if ALLOW_DEPRECATED_FUNCTIONS
|
||||||
}
|
|
||||||
//------------------------------------------------------------------------------
|
|
||||||
// Deprecated functions - suppress cpplint warnings with NOLINT comment
|
|
||||||
#if ALLOW_DEPRECATED_FUNCTIONS && !defined(DOXYGEN)
|
|
||||||
public:
|
public:
|
||||||
/** \deprecated Use: bool SdVolume::init(Sd2Card* dev);
|
/**
|
||||||
|
* \deprecated Use: bool SdVolume::init(Sd2Card* dev);
|
||||||
* \param[in] dev The SD card where the volume is located.
|
* \param[in] dev The SD card where the volume is located.
|
||||||
* \return true for success or false for failure.
|
* \return true for success or false for failure.
|
||||||
*/
|
*/
|
||||||
bool init(Sd2Card& dev) {return init(&dev);} // NOLINT
|
bool init(Sd2Card& dev) { return init(&dev); }
|
||||||
/** \deprecated Use: bool SdVolume::init(Sd2Card* dev, uint8_t vol);
|
/**
|
||||||
|
* \deprecated Use: bool SdVolume::init(Sd2Card* dev, uint8_t vol);
|
||||||
* \param[in] dev The SD card where the volume is located.
|
* \param[in] dev The SD card where the volume is located.
|
||||||
* \param[in] part The partition to be used.
|
* \param[in] part The partition to be used.
|
||||||
* \return true for success or false for failure.
|
* \return true for success or false for failure.
|
||||||
*/
|
*/
|
||||||
bool init(Sd2Card& dev, uint8_t part) { // NOLINT
|
bool init(Sd2Card& dev, uint8_t part) { return init(&dev, part); }
|
||||||
return init(&dev, part);
|
#endif // ALLOW_DEPRECATED_FUNCTIONS
|
||||||
}
|
|
||||||
#endif // ALLOW_DEPRECATED_FUNCTIONS
|
|
||||||
};
|
};
|
||||||
#endif // SdVolume
|
|
||||||
#endif
|
#endif // _SDVOLUME_H_
|
||||||
|
|||||||
@@ -48,7 +48,7 @@
|
|||||||
* here we define this default string as the date where the latest release
|
* here we define this default string as the date where the latest release
|
||||||
* version was tagged.
|
* version was tagged.
|
||||||
*/
|
*/
|
||||||
#define STRING_DISTRIBUTION_DATE "2017-10-10 12:00"
|
#define STRING_DISTRIBUTION_DATE "2017-10-24 12:00"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Required minimum Configuration.h and Configuration_adv.h file versions.
|
* Required minimum Configuration.h and Configuration_adv.h file versions.
|
||||||
@@ -57,8 +57,8 @@
|
|||||||
* but not limited to: ADD, DELETE RENAME OR REPURPOSE any directive/option on
|
* but not limited to: ADD, DELETE RENAME OR REPURPOSE any directive/option on
|
||||||
* the configuration files.
|
* the configuration files.
|
||||||
*/
|
*/
|
||||||
#define REQUIRED_CONFIGURATION_H_VERSION 010100
|
#define REQUIRED_CONFIGURATION_H_VERSION 010107
|
||||||
#define REQUIRED_CONFIGURATION_ADV_H_VERSION 010100
|
#define REQUIRED_CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* The protocol for communication to the host. Protocol indicates communication
|
* The protocol for communication to the host. Protocol indicates communication
|
||||||
|
|||||||
38
Marlin/bitmap_flags.h
Normal file
38
Marlin/bitmap_flags.h
Normal file
@@ -0,0 +1,38 @@
|
|||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016, 2017 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 _BITMAP_FLAGS_H_
|
||||||
|
#define _BITMAP_FLAGS_H_
|
||||||
|
|
||||||
|
#include "macros.h"
|
||||||
|
|
||||||
|
/**
|
||||||
|
* These support functions allow the use of large bit arrays of flags that take very
|
||||||
|
* little RAM. Currently they are limited to being 16x16 in size. Changing the declaration
|
||||||
|
* to unsigned long will allow us to go to 32x32 if higher resolution meshes are needed
|
||||||
|
* in the future.
|
||||||
|
*/
|
||||||
|
FORCE_INLINE void bitmap_clear(uint16_t bits[16], const uint8_t x, const uint8_t y) { CBI(bits[y], x); }
|
||||||
|
FORCE_INLINE void bitmap_set(uint16_t bits[16], const uint8_t x, const uint8_t y) { SBI(bits[y], x); }
|
||||||
|
FORCE_INLINE bool is_bitmap_set(uint16_t bits[16], const uint8_t x, const uint8_t y) { return TEST(bits[y], x); }
|
||||||
|
|
||||||
|
#endif // _BITMAP_FLAGS_H_
|
||||||
@@ -21,26 +21,26 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* blinkm.cpp - Library for controlling a BlinkM over i2c
|
* blinkm.cpp - Control a BlinkM over i2c
|
||||||
* Created by Tim Koster, August 21 2013.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "Marlin.h"
|
#include "MarlinConfig.h"
|
||||||
|
|
||||||
#if ENABLED(BLINKM)
|
#if ENABLED(BLINKM)
|
||||||
|
|
||||||
#include "blinkm.h"
|
#include "blinkm.h"
|
||||||
|
#include "leds.h"
|
||||||
|
#include <Wire.h>
|
||||||
|
|
||||||
void SendColors(byte red, byte grn, byte blu) {
|
void blinkm_set_led_color(const LEDColor &color) {
|
||||||
Wire.begin();
|
Wire.begin();
|
||||||
Wire.beginTransmission(0x09);
|
Wire.beginTransmission(0x09);
|
||||||
Wire.write('o'); //to disable ongoing script, only needs to be used once
|
Wire.write('o'); //to disable ongoing script, only needs to be used once
|
||||||
Wire.write('n');
|
Wire.write('n');
|
||||||
Wire.write(red);
|
Wire.write(color.r);
|
||||||
Wire.write(grn);
|
Wire.write(color.g);
|
||||||
Wire.write(blu);
|
Wire.write(color.b);
|
||||||
Wire.endTransmission();
|
Wire.endTransmission();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // BLINKM
|
#endif // BLINKM
|
||||||
|
|
||||||
|
|||||||
@@ -21,11 +21,15 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* blinkm.h - Library for controlling a BlinkM over i2c
|
* blinkm.h - Control a BlinkM over i2c
|
||||||
* Created by Tim Koster, August 21 2013.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "Arduino.h"
|
#ifndef _BLINKM_H_
|
||||||
#include "Wire.h"
|
#define _BLINKM_H_
|
||||||
|
|
||||||
void SendColors(byte red, byte grn, byte blu);
|
struct LEDColor;
|
||||||
|
typedef LEDColor LEDColor;
|
||||||
|
|
||||||
|
void blinkm_set_led_color(const LEDColor &color);
|
||||||
|
|
||||||
|
#endif // _BLINKM_H_
|
||||||
|
|||||||
144
Marlin/boards.h
144
Marlin/boards.h
@@ -25,32 +25,90 @@
|
|||||||
|
|
||||||
#define BOARD_UNKNOWN -1
|
#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
|
// RAMPS 1.3 / 1.4 - ATmega1280, ATmega2560
|
||||||
#define BOARD_GEN7_13 12 // Gen7 v1.3
|
//
|
||||||
#define BOARD_GEN7_14 13 // Gen7 v1.4
|
|
||||||
#define BOARD_CNCONTROLS_11 111 // Cartesio CN Controls V11
|
|
||||||
#define BOARD_CNCONTROLS_12 112 // Cartesio CN Controls V12
|
|
||||||
#define BOARD_CHEAPTRONIC 2 // Cheaptronic v1.0
|
|
||||||
#define BOARD_CHEAPTRONIC_V2 21 // Cheaptronic v2.0
|
|
||||||
#define BOARD_SETHI 20 // Sethi 3D_1
|
|
||||||
#define BOARD_MIGHTYBOARD_REVE 200 // Makerbot Mightyboard Revision E
|
|
||||||
#define BOARD_RAMPS_OLD 3 // MEGA/RAMPS up to 1.2
|
#define BOARD_RAMPS_OLD 3 // MEGA/RAMPS up to 1.2
|
||||||
|
|
||||||
#define BOARD_RAMPS_13_EFB 33 // RAMPS 1.3 (Power outputs: Hotend, Fan, Bed)
|
#define BOARD_RAMPS_13_EFB 33 // RAMPS 1.3 (Power outputs: Hotend, Fan, Bed)
|
||||||
#define BOARD_RAMPS_13_EEB 34 // RAMPS 1.3 (Power outputs: Hotend0, Hotend1, Bed)
|
#define BOARD_RAMPS_13_EEB 34 // RAMPS 1.3 (Power outputs: Hotend0, Hotend1, Bed)
|
||||||
#define BOARD_RAMPS_13_EFF 35 // RAMPS 1.3 (Power outputs: Hotend, Fan0, Fan1)
|
#define BOARD_RAMPS_13_EFF 35 // RAMPS 1.3 (Power outputs: Hotend, Fan0, Fan1)
|
||||||
#define BOARD_RAMPS_13_EEF 36 // RAMPS 1.3 (Power outputs: Hotend0, Hotend1, Fan)
|
#define BOARD_RAMPS_13_EEF 36 // RAMPS 1.3 (Power outputs: Hotend0, Hotend1, Fan)
|
||||||
#define BOARD_RAMPS_13_SF 38 // RAMPS 1.3 (Power outputs: Spindle, Controller Fan)
|
#define BOARD_RAMPS_13_SF 38 // RAMPS 1.3 (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_RIGIDBOARD_V2 52 // Invent-A-Part RigidBoard V2
|
|
||||||
#define BOARD_RAMPS_14_EFB 43 // RAMPS 1.4 (Power outputs: Hotend, Fan, Bed)
|
#define BOARD_RAMPS_14_EFB 43 // RAMPS 1.4 (Power outputs: Hotend, Fan, Bed)
|
||||||
#define BOARD_RAMPS_14_EEB 44 // RAMPS 1.4 (Power outputs: Hotend0, Hotend1, Bed)
|
#define BOARD_RAMPS_14_EEB 44 // RAMPS 1.4 (Power outputs: Hotend0, Hotend1, Bed)
|
||||||
#define BOARD_RAMPS_14_EFF 45 // RAMPS 1.4 (Power outputs: Hotend, Fan0, Fan1)
|
#define BOARD_RAMPS_14_EFF 45 // RAMPS 1.4 (Power outputs: Hotend, Fan0, Fan1)
|
||||||
#define BOARD_RAMPS_14_EEF 46 // RAMPS 1.4 (Power outputs: Hotend0, Hotend1, Fan)
|
#define BOARD_RAMPS_14_EEF 46 // RAMPS 1.4 (Power outputs: Hotend0, Hotend1, Fan)
|
||||||
#define BOARD_RAMPS_14_SF 48 // RAMPS 1.4 (Power outputs: Spindle, Controller Fan)
|
#define BOARD_RAMPS_14_SF 48 // RAMPS 1.4 (Power outputs: Spindle, Controller Fan)
|
||||||
#define BOARD_GEN6 5 // Gen6
|
|
||||||
#define BOARD_GEN6_DELUXE 51 // Gen6 deluxe
|
#define BOARD_RAMPS_PLUS_EFB 143 // RAMPS Plus 3DYMY (Power outputs: Hotend, Fan, Bed)
|
||||||
|
#define BOARD_RAMPS_PLUS_EEB 144 // RAMPS Plus 3DYMY (Power outputs: Hotend0, Hotend1, Bed)
|
||||||
|
#define BOARD_RAMPS_PLUS_EFF 145 // RAMPS Plus 3DYMY (Power outputs: Hotend, Fan0, Fan1)
|
||||||
|
#define BOARD_RAMPS_PLUS_EEF 146 // RAMPS Plus 3DYMY (Power outputs: Hotend0, Hotend1, Fan)
|
||||||
|
#define BOARD_RAMPS_PLUS_SF 148 // RAMPS Plus 3DYMY (Power outputs: Spindle, Controller Fan)
|
||||||
|
|
||||||
|
//
|
||||||
|
// RAMPS Derivatives - ATmega1280, ATmega2560
|
||||||
|
//
|
||||||
|
|
||||||
|
#define BOARD_3DRAG 77 // 3Drag Controller
|
||||||
|
#define BOARD_K8200 78 // Velleman K8200 Controller (derived from 3Drag Controller)
|
||||||
|
#define BOARD_K8400 79 // Velleman K8400 Controller (derived from 3Drag Controller)
|
||||||
|
#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_MKS_BASE 40 // MKS BASE 1.0
|
||||||
|
#define BOARD_MKS_13 47 // MKS v1.3 or 1.4 (maybe higher)
|
||||||
|
#define BOARD_MKS_GEN_L 53 // MKS GEN L
|
||||||
|
#define BOARD_ZRIB_V20 504 // zrib V2.0 control board (Chinese knock off RAMPS replica)
|
||||||
|
#define BOARD_FELIX2 37 // Felix 2.0+ Electronics Board (RAMPS like)
|
||||||
|
#define BOARD_RIGIDBOARD 42 // Invent-A-Part RigidBoard
|
||||||
|
#define BOARD_RIGIDBOARD_V2 52 // Invent-A-Part RigidBoard V2
|
||||||
|
#define BOARD_SAINSMART_2IN1 49 // Sainsmart 2-in-1 board
|
||||||
|
#define BOARD_ULTIMAKER 7 // Ultimaker
|
||||||
|
#define BOARD_ULTIMAKER_OLD 71 // Ultimaker (Older electronics. Pre 1.5.4. This is rare)
|
||||||
|
#define BOARD_AZTEEG_X3 67 // Azteeg X3
|
||||||
|
#define BOARD_AZTEEG_X3_PRO 68 // Azteeg X3 Pro
|
||||||
|
#define BOARD_ULTIMAIN_2 72 // Ultimainboard 2.x (Uses TEMP_SENSOR 20)
|
||||||
|
#define BOARD_RUMBA 80 // Rumba
|
||||||
|
#define BOARD_BQ_ZUM_MEGA_3D 503 // bq ZUM Mega 3D
|
||||||
|
#define BOARD_MAKEBOARD_MINI 431 // MakeBoard Mini v2.1.2 is a control board sold by MicroMake
|
||||||
|
|
||||||
|
//
|
||||||
|
// Other ATmega1280, ATmega2560
|
||||||
|
//
|
||||||
|
|
||||||
|
#define BOARD_CNCONTROLS_11 111 // Cartesio CN Controls V11
|
||||||
|
#define BOARD_CNCONTROLS_12 112 // Cartesio CN Controls V12
|
||||||
|
#define BOARD_CHEAPTRONIC 2 // Cheaptronic v1.0
|
||||||
|
#define BOARD_CHEAPTRONIC_V2 21 // Cheaptronic v2.0
|
||||||
|
#define BOARD_MIGHTYBOARD_REVE 200 // Makerbot Mightyboard Revision E
|
||||||
|
#define BOARD_MEGATRONICS 70 // Megatronics
|
||||||
|
#define BOARD_MEGATRONICS_2 701 // Megatronics v2.0
|
||||||
|
#define BOARD_MEGATRONICS_3 703 // Megatronics v3.0
|
||||||
|
#define BOARD_MEGATRONICS_31 704 // Megatronics v3.1
|
||||||
|
#define BOARD_RAMBO 301 // Rambo
|
||||||
|
#define BOARD_MINIRAMBO 302 // Mini-Rambo
|
||||||
|
#define BOARD_MINIRAMBO_10A 303 // Mini-Rambo 1.0a
|
||||||
|
#define BOARD_ELEFU_3 21 // Elefu Ra Board (v3)
|
||||||
|
#define BOARD_LEAPFROG 999 // Leapfrog
|
||||||
|
#define BOARD_MEGACONTROLLER 310 // Mega controller
|
||||||
|
#define BOARD_SCOOVO_X9H 321 // abee Scoovo X9H
|
||||||
|
#define BOARD_GT2560_REV_A 74 // Geeetech GT2560 Rev. A
|
||||||
|
#define BOARD_GT2560_REV_A_PLUS 75 // Geeetech GT2560 Rev. A+ (with auto level probe)
|
||||||
|
|
||||||
|
//
|
||||||
|
// ATmega1281, ATmega2561
|
||||||
|
//
|
||||||
|
|
||||||
|
#define BOARD_MINITRONICS 702 // Minitronics v1.0/1.1
|
||||||
|
#define BOARD_SILVER_GATE 25 // Silvergate v1.0
|
||||||
|
|
||||||
|
//
|
||||||
|
// Sanguinololu and Derivatives - ATmega644P, ATmega1284P
|
||||||
|
//
|
||||||
|
|
||||||
#define BOARD_SANGUINOLOLU_11 6 // Sanguinololu < 1.2
|
#define BOARD_SANGUINOLOLU_11 6 // Sanguinololu < 1.2
|
||||||
#define BOARD_SANGUINOLOLU_12 62 // Sanguinololu 1.2 and above
|
#define BOARD_SANGUINOLOLU_12 62 // Sanguinololu 1.2 and above
|
||||||
#define BOARD_MELZI 63 // Melzi
|
#define BOARD_MELZI 63 // Melzi
|
||||||
@@ -58,48 +116,36 @@
|
|||||||
#define BOARD_MELZI_CREALITY 89 // Melzi Creality3D board (for CR-10 etc)
|
#define BOARD_MELZI_CREALITY 89 // Melzi Creality3D board (for CR-10 etc)
|
||||||
#define BOARD_STB_11 64 // STB V1.1
|
#define BOARD_STB_11 64 // STB V1.1
|
||||||
#define BOARD_AZTEEG_X1 65 // Azteeg X1
|
#define BOARD_AZTEEG_X1 65 // Azteeg X1
|
||||||
#define BOARD_AZTEEG_X3 67 // Azteeg X3
|
|
||||||
#define BOARD_AZTEEG_X3_PRO 68 // Azteeg X3 Pro
|
//
|
||||||
|
// Other ATmega644P, ATmega644, ATmega1284P
|
||||||
|
//
|
||||||
|
|
||||||
|
#define BOARD_GEN3_MONOLITHIC 22 // Gen3 Monolithic Electronics
|
||||||
|
#define BOARD_GEN3_PLUS 9 // Gen3+
|
||||||
|
#define BOARD_GEN6 5 // Gen6
|
||||||
|
#define BOARD_GEN6_DELUXE 51 // Gen6 deluxe
|
||||||
|
#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_OMCA_A 90 // Alpha OMCA board
|
||||||
|
#define BOARD_OMCA 91 // Final OMCA board
|
||||||
|
#define BOARD_SETHI 20 // Sethi 3D_1
|
||||||
#define BOARD_ANET_10 69 // Anet 1.0 (Melzi clone)
|
#define BOARD_ANET_10 69 // Anet 1.0 (Melzi clone)
|
||||||
#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)
|
// Teensyduino - AT90USB1286, AT90USB1286P
|
||||||
#define BOARD_GT2560_REV_A 74 // Geeetech GT2560 Rev. A
|
//
|
||||||
#define BOARD_GT2560_REV_A_PLUS 75 // Geeetech GT2560 Rev. A+ (with auto level probe)
|
|
||||||
#define BOARD_3DRAG 77 // 3Drag Controller
|
|
||||||
#define BOARD_K8200 78 // Velleman K8200 Controller (derived from 3Drag Controller)
|
|
||||||
#define BOARD_K8400 79 // Velleman K8400 Controller (derived from 3Drag Controller)
|
|
||||||
#define BOARD_TEENSYLU 8 // Teensylu
|
#define BOARD_TEENSYLU 8 // Teensylu
|
||||||
#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_PRINTRBOARD_REVF 811 // Printrboard Revision F (AT90USB1286)
|
||||||
#define BOARD_BRAINWAVE 82 // Brainwave (AT90USB646)
|
#define BOARD_BRAINWAVE 82 // Brainwave (AT90USB646)
|
||||||
|
#define BOARD_BRAINWAVE_PRO 85 // Brainwave Pro (AT90USB1286)
|
||||||
#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: HARDWARE_MOTHERBOARD=84 make
|
#define BOARD_TEENSY2 84 // Teensy++2.0 (AT90USB1286) - CLI compile: 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_MEGATRONICS_31 704 // Megatronics v3.1
|
|
||||||
#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_SCOOVO_X9H 303 // abee Scoovo X9H
|
|
||||||
#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_5DPRINT 88 // 5DPrint D8 Driver Board
|
||||||
#define BOARD_LEAPFROG 999 // Leapfrog
|
|
||||||
#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_DUE 402 // 2PrintBeta BAM&DICE Due with STK drivers
|
|
||||||
#define BOARD_BQ_ZUM_MEGA_3D 503 // bq ZUM Mega 3D
|
|
||||||
#define BOARD_ZRIB_V20 504 // zrib V2.0 control board (Chinese knock off RAMPS replica)
|
|
||||||
|
|
||||||
#define MB(board) (MOTHERBOARD==BOARD_##board)
|
#define MB(board) (MOTHERBOARD==BOARD_##board)
|
||||||
|
|
||||||
|
|||||||
@@ -20,16 +20,16 @@
|
|||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include "MarlinConfig.h"
|
||||||
|
|
||||||
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
#include "cardreader.h"
|
#include "cardreader.h"
|
||||||
|
|
||||||
#include "ultralcd.h"
|
#include "ultralcd.h"
|
||||||
#include "stepper.h"
|
#include "stepper.h"
|
||||||
#include "language.h"
|
#include "language.h"
|
||||||
|
|
||||||
#include "Marlin.h"
|
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
|
||||||
|
|
||||||
#define LONGEST_FILENAME (longFilename[0] ? longFilename : filename)
|
#define LONGEST_FILENAME (longFilename[0] ? longFilename : filename)
|
||||||
|
|
||||||
CardReader::CardReader() {
|
CardReader::CardReader() {
|
||||||
@@ -44,8 +44,9 @@ CardReader::CardReader() {
|
|||||||
sdprinting = cardOK = saving = logging = false;
|
sdprinting = cardOK = saving = logging = false;
|
||||||
filesize = 0;
|
filesize = 0;
|
||||||
sdpos = 0;
|
sdpos = 0;
|
||||||
workDirDepth = 0;
|
|
||||||
file_subcall_ctr = 0;
|
file_subcall_ctr = 0;
|
||||||
|
|
||||||
|
workDirDepth = 0;
|
||||||
ZERO(workDirParents);
|
ZERO(workDirParents);
|
||||||
|
|
||||||
autostart_stilltocheck = true; //the SD start is delayed, because otherwise the serial cannot answer fast enough to make contact with the host software.
|
autostart_stilltocheck = true; //the SD start is delayed, because otherwise the serial cannot answer fast enough to make contact with the host software.
|
||||||
@@ -73,9 +74,12 @@ char *createFilename(char *buffer, const dir_t &p) { //buffer > 12characters
|
|||||||
/**
|
/**
|
||||||
* Dive into a folder and recurse depth-first to perform a pre-set operation lsAction:
|
* Dive into a folder and recurse depth-first to perform a pre-set operation lsAction:
|
||||||
* LS_Count - Add +1 to nrFiles for every file within the parent
|
* LS_Count - Add +1 to nrFiles for every file within the parent
|
||||||
* LS_GetFilename - Get the filename of the file indexed by nrFiles
|
* LS_GetFilename - Get the filename of the file indexed by nrFile_index
|
||||||
* LS_SerialPrint - Print the full path and size of each file to serial output
|
* LS_SerialPrint - Print the full path and size of each file to serial output
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
uint16_t nrFile_index;
|
||||||
|
|
||||||
void CardReader::lsDive(const char *prepend, SdFile parent, const char * const match/*=NULL*/) {
|
void CardReader::lsDive(const char *prepend, SdFile parent, const char * const match/*=NULL*/) {
|
||||||
dir_t p;
|
dir_t p;
|
||||||
uint8_t cnt = 0;
|
uint8_t cnt = 0;
|
||||||
@@ -129,7 +133,7 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
|
|||||||
|
|
||||||
if (!filenameIsDir && (p.name[8] != 'G' || p.name[9] == '~')) continue;
|
if (!filenameIsDir && (p.name[8] != 'G' || p.name[9] == '~')) continue;
|
||||||
|
|
||||||
switch (lsAction) {
|
switch (lsAction) { // 1 based file count
|
||||||
case LS_Count:
|
case LS_Count:
|
||||||
nrFiles++;
|
nrFiles++;
|
||||||
break;
|
break;
|
||||||
@@ -147,7 +151,7 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
|
|||||||
if (match != NULL) {
|
if (match != NULL) {
|
||||||
if (strcasecmp(match, filename) == 0) return;
|
if (strcasecmp(match, filename) == 0) return;
|
||||||
}
|
}
|
||||||
else if (cnt == nrFiles) return;
|
else if (cnt == nrFile_index) return; // 0 based index
|
||||||
cnt++;
|
cnt++;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@@ -255,16 +259,7 @@ void CardReader::initsd() {
|
|||||||
SERIAL_ECHO_START();
|
SERIAL_ECHO_START();
|
||||||
SERIAL_ECHOLNPGM(MSG_SD_CARD_OK);
|
SERIAL_ECHOLNPGM(MSG_SD_CARD_OK);
|
||||||
}
|
}
|
||||||
workDir = root;
|
setroot();
|
||||||
curDir = &root;
|
|
||||||
#if ENABLED(SDCARD_SORT_ALPHA)
|
|
||||||
presort();
|
|
||||||
#endif
|
|
||||||
/**
|
|
||||||
if (!workDir.openRoot(&volume)) {
|
|
||||||
SERIAL_ECHOLNPGM(MSG_SD_WORKDIR_FAIL);
|
|
||||||
}
|
|
||||||
*/
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void CardReader::setroot() {
|
void CardReader::setroot() {
|
||||||
@@ -310,26 +305,33 @@ void CardReader::openLogFile(char* name) {
|
|||||||
openFile(name, false);
|
openFile(name, false);
|
||||||
}
|
}
|
||||||
|
|
||||||
void CardReader::getAbsFilename(char *t) {
|
void appendAtom(SdFile &file, char *& dst, uint8_t &cnt) {
|
||||||
uint8_t cnt = 0;
|
file.getFilename(dst);
|
||||||
*t = '/'; t++; cnt++;
|
while (*dst && cnt < MAXPATHNAMELENGTH) { dst++; cnt++; }
|
||||||
for (uint8_t i = 0; i < workDirDepth; i++) {
|
if (cnt < MAXPATHNAMELENGTH) { *dst = '/'; dst++; cnt++; }
|
||||||
workDirParents[i].getFilename(t); //SDBaseFile.getfilename!
|
|
||||||
while (*t && cnt < MAXPATHNAMELENGTH) { t++; cnt++; } //crawl counter forward.
|
|
||||||
}
|
|
||||||
if (cnt < MAXPATHNAMELENGTH - (FILENAME_LENGTH))
|
|
||||||
file.getFilename(t);
|
|
||||||
else
|
|
||||||
t[0] = 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
|
void CardReader::getAbsFilename(char *t) {
|
||||||
|
*t++ = '/'; // Root folder
|
||||||
|
uint8_t cnt = 1;
|
||||||
|
|
||||||
|
for (uint8_t i = 0; i < workDirDepth; i++) // Loop to current work dir
|
||||||
|
appendAtom(workDirParents[i], t, cnt);
|
||||||
|
|
||||||
|
if (cnt < MAXPATHNAMELENGTH - (FILENAME_LENGTH)) {
|
||||||
|
appendAtom(file, t, cnt);
|
||||||
|
--t;
|
||||||
|
}
|
||||||
|
*t = '\0';
|
||||||
|
}
|
||||||
|
|
||||||
|
void CardReader::openFile(char* name, const bool read, const bool subcall/*=false*/) {
|
||||||
|
|
||||||
if (!cardOK) return;
|
if (!cardOK) return;
|
||||||
|
|
||||||
uint8_t doing = 0;
|
uint8_t doing = 0;
|
||||||
if (isFileOpen()) { //replacing current file by new file, or subfile call
|
if (isFileOpen()) { // Replacing current file or doing a subroutine
|
||||||
if (push_current) {
|
if (subcall) {
|
||||||
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:");
|
||||||
@@ -338,19 +340,22 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Store current filename and position
|
// Store current filename (based on workDirParents) and position
|
||||||
getAbsFilename(proc_filenames[file_subcall_ctr]);
|
getAbsFilename(proc_filenames[file_subcall_ctr]);
|
||||||
|
filespos[file_subcall_ctr] = sdpos;
|
||||||
|
|
||||||
SERIAL_ECHO_START();
|
SERIAL_ECHO_START();
|
||||||
SERIAL_ECHOPAIR("SUBROUTINE CALL target:\"", name);
|
SERIAL_ECHOPAIR("SUBROUTINE CALL target:\"", name);
|
||||||
SERIAL_ECHOPAIR("\" parent:\"", proc_filenames[file_subcall_ctr]);
|
SERIAL_ECHOPAIR("\" parent:\"", proc_filenames[file_subcall_ctr]);
|
||||||
SERIAL_ECHOLNPAIR("\" pos", sdpos);
|
SERIAL_ECHOLNPAIR("\" pos", sdpos);
|
||||||
filespos[file_subcall_ctr] = sdpos;
|
|
||||||
file_subcall_ctr++;
|
file_subcall_ctr++;
|
||||||
}
|
}
|
||||||
else {
|
else
|
||||||
doing = 1;
|
doing = 1;
|
||||||
}
|
}
|
||||||
|
else if (subcall) { // Returning from a subcall?
|
||||||
|
SERIAL_ECHO_START();
|
||||||
|
SERIAL_ECHOLNPGM("END SUBROUTINE");
|
||||||
}
|
}
|
||||||
else { // Opening fresh file
|
else { // Opening fresh file
|
||||||
doing = 2;
|
doing = 2;
|
||||||
@@ -360,7 +365,7 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
|
|||||||
if (doing) {
|
if (doing) {
|
||||||
SERIAL_ECHO_START();
|
SERIAL_ECHO_START();
|
||||||
SERIAL_ECHOPGM("Now ");
|
SERIAL_ECHOPGM("Now ");
|
||||||
SERIAL_ECHO(doing == 1 ? "doing" : "fresh");
|
serialprintPGM(doing == 1 ? PSTR("doing") : PSTR("fresh"));
|
||||||
SERIAL_ECHOLNPAIR(" file: ", name);
|
SERIAL_ECHOLNPAIR(" file: ", name);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -380,8 +385,7 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
|
|||||||
if (dirname_end != NULL && 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';
|
||||||
SERIAL_ECHOLN(subdirname);
|
|
||||||
if (!myDir.open(curDir, subdirname, O_READ)) {
|
if (!myDir.open(curDir, subdirname, O_READ)) {
|
||||||
SERIAL_PROTOCOLPGM(MSG_SD_OPEN_FILE_FAIL);
|
SERIAL_PROTOCOLPGM(MSG_SD_OPEN_FILE_FAIL);
|
||||||
SERIAL_PROTOCOL(subdirname);
|
SERIAL_PROTOCOL(subdirname);
|
||||||
@@ -403,17 +407,15 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else { //relative path
|
else
|
||||||
curDir = &workDir;
|
curDir = &workDir; // Relative paths start in current directory
|
||||||
}
|
|
||||||
|
|
||||||
if (read) {
|
if (read) {
|
||||||
if (file.open(curDir, fname, O_READ)) {
|
if (file.open(curDir, fname, O_READ)) {
|
||||||
filesize = file.fileSize();
|
filesize = file.fileSize();
|
||||||
|
sdpos = 0;
|
||||||
SERIAL_PROTOCOLPAIR(MSG_SD_FILE_OPENED, fname);
|
SERIAL_PROTOCOLPAIR(MSG_SD_FILE_OPENED, fname);
|
||||||
SERIAL_PROTOCOLLNPAIR(MSG_SD_SIZE, filesize);
|
SERIAL_PROTOCOLLNPAIR(MSG_SD_SIZE, filesize);
|
||||||
sdpos = 0;
|
|
||||||
|
|
||||||
SERIAL_PROTOCOLLNPGM(MSG_SD_FILE_SELECTED);
|
SERIAL_PROTOCOLLNPGM(MSG_SD_FILE_SELECTED);
|
||||||
getfilename(0, fname);
|
getfilename(0, fname);
|
||||||
lcd_setstatus(longFilename[0] ? longFilename : fname);
|
lcd_setstatus(longFilename[0] ? longFilename : fname);
|
||||||
@@ -438,14 +440,14 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void CardReader::removeFile(char* name) {
|
void CardReader::removeFile(const char * const name) {
|
||||||
if (!cardOK) return;
|
if (!cardOK) return;
|
||||||
|
|
||||||
stopSDPrint();
|
stopSDPrint();
|
||||||
|
|
||||||
SdFile myDir;
|
SdFile myDir;
|
||||||
curDir = &root;
|
curDir = &root;
|
||||||
char *fname = name;
|
const char *fname = name;
|
||||||
|
|
||||||
char *dirname_start, *dirname_end;
|
char *dirname_start, *dirname_end;
|
||||||
if (name[0] == '/') {
|
if (name[0] == '/') {
|
||||||
@@ -460,29 +462,23 @@ void CardReader::removeFile(char* name) {
|
|||||||
subdirname[dirname_end - dirname_start] = 0;
|
subdirname[dirname_end - dirname_start] = 0;
|
||||||
SERIAL_ECHOLN(subdirname);
|
SERIAL_ECHOLN(subdirname);
|
||||||
if (!myDir.open(curDir, subdirname, O_READ)) {
|
if (!myDir.open(curDir, subdirname, O_READ)) {
|
||||||
SERIAL_PROTOCOLPAIR("open failed, File: ", subdirname);
|
SERIAL_PROTOCOLPAIR(MSG_SD_OPEN_FILE_FAIL, subdirname);
|
||||||
SERIAL_PROTOCOLCHAR('.');
|
SERIAL_PROTOCOLCHAR('.');
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
else {
|
|
||||||
//SERIAL_ECHOLNPGM("dive ok");
|
|
||||||
}
|
|
||||||
|
|
||||||
curDir = &myDir;
|
curDir = &myDir;
|
||||||
dirname_start = dirname_end + 1;
|
dirname_start = dirname_end + 1;
|
||||||
}
|
}
|
||||||
else { // the remainder after all /fsa/fdsa/ is the filename
|
else {
|
||||||
fname = dirname_start;
|
fname = dirname_start;
|
||||||
//SERIAL_ECHOLNPGM("remainder");
|
|
||||||
//SERIAL_ECHOLN(fname);
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else { // relative path
|
else // Relative paths are rooted in the current directory
|
||||||
curDir = &workDir;
|
curDir = &workDir;
|
||||||
}
|
|
||||||
|
|
||||||
if (file.remove(curDir, fname)) {
|
if (file.remove(curDir, fname)) {
|
||||||
SERIAL_PROTOCOLPGM("File deleted:");
|
SERIAL_PROTOCOLPGM("File deleted:");
|
||||||
@@ -506,14 +502,13 @@ void CardReader::getStatus() {
|
|||||||
SERIAL_PROTOCOLCHAR('/');
|
SERIAL_PROTOCOLCHAR('/');
|
||||||
SERIAL_PROTOCOLLN(filesize);
|
SERIAL_PROTOCOLLN(filesize);
|
||||||
}
|
}
|
||||||
else {
|
else
|
||||||
SERIAL_PROTOCOLLNPGM(MSG_SD_NOT_PRINTING);
|
SERIAL_PROTOCOLLNPGM(MSG_SD_NOT_PRINTING);
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void CardReader::write_command(char *buf) {
|
void CardReader::write_command(char *buf) {
|
||||||
char* begin = buf;
|
char* begin = buf;
|
||||||
char* npos = 0;
|
char* npos = NULL;
|
||||||
char* end = buf + strlen(buf) - 1;
|
char* end = buf + strlen(buf) - 1;
|
||||||
|
|
||||||
file.writeError = false;
|
file.writeError = false;
|
||||||
@@ -595,7 +590,7 @@ void CardReader::getfilename(uint16_t nr, const char * const match/*=NULL*/) {
|
|||||||
#endif // SDSORT_CACHE_NAMES
|
#endif // SDSORT_CACHE_NAMES
|
||||||
curDir = &workDir;
|
curDir = &workDir;
|
||||||
lsAction = LS_GetFilename;
|
lsAction = LS_GetFilename;
|
||||||
nrFiles = nr;
|
nrFile_index = nr;
|
||||||
curDir->rewind();
|
curDir->rewind();
|
||||||
lsDive("", *curDir, match);
|
lsDive("", *curDir, match);
|
||||||
}
|
}
|
||||||
@@ -611,33 +606,34 @@ uint16_t CardReader::getnrfilenames() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void CardReader::chdir(const char * relpath) {
|
void CardReader::chdir(const char * relpath) {
|
||||||
SdFile newfile;
|
SdFile newDir;
|
||||||
SdFile *parent = &root;
|
SdFile *parent = &root;
|
||||||
|
|
||||||
if (workDir.isOpen()) parent = &workDir;
|
if (workDir.isOpen()) parent = &workDir;
|
||||||
|
|
||||||
if (!newfile.open(*parent, relpath, O_READ)) {
|
if (!newDir.open(*parent, relpath, O_READ)) {
|
||||||
SERIAL_ECHO_START();
|
SERIAL_ECHO_START();
|
||||||
SERIAL_ECHOPGM(MSG_SD_CANT_ENTER_SUBDIR);
|
SERIAL_ECHOPGM(MSG_SD_CANT_ENTER_SUBDIR);
|
||||||
SERIAL_ECHOLN(relpath);
|
SERIAL_ECHOLN(relpath);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
workDir = newDir;
|
||||||
if (workDirDepth < MAX_DIR_DEPTH)
|
if (workDirDepth < MAX_DIR_DEPTH)
|
||||||
workDirParents[workDirDepth++] = *parent;
|
workDirParents[workDirDepth++] = workDir;
|
||||||
workDir = newfile;
|
|
||||||
#if ENABLED(SDCARD_SORT_ALPHA)
|
#if ENABLED(SDCARD_SORT_ALPHA)
|
||||||
presort();
|
presort();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void CardReader::updir() {
|
int8_t CardReader::updir() {
|
||||||
if (workDirDepth > 0) {
|
if (workDirDepth > 0) { // At least 1 dir has been saved
|
||||||
workDir = workDirParents[--workDirDepth];
|
workDir = --workDirDepth ? workDirParents[workDirDepth - 1] : root; // Use parent, or root if none
|
||||||
#if ENABLED(SDCARD_SORT_ALPHA)
|
#if ENABLED(SDCARD_SORT_ALPHA)
|
||||||
presort();
|
presort();
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
return workDirDepth;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if ENABLED(SDCARD_SORT_ALPHA)
|
#if ENABLED(SDCARD_SORT_ALPHA)
|
||||||
@@ -696,7 +692,7 @@ void CardReader::updir() {
|
|||||||
sortnames = new char*[fileCnt];
|
sortnames = new char*[fileCnt];
|
||||||
#endif
|
#endif
|
||||||
#elif ENABLED(SDSORT_USES_STACK)
|
#elif ENABLED(SDSORT_USES_STACK)
|
||||||
char sortnames[fileCnt][LONG_FILENAME_LENGTH];
|
char sortnames[fileCnt][SORTED_LONGNAME_MAXLEN];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Folder sorting needs 1 bit per entry for flags.
|
// Folder sorting needs 1 bit per entry for flags.
|
||||||
@@ -735,7 +731,12 @@ void CardReader::updir() {
|
|||||||
#endif
|
#endif
|
||||||
#else
|
#else
|
||||||
// Copy filenames into the static array
|
// Copy filenames into the static array
|
||||||
strcpy(sortnames[i], LONGEST_FILENAME);
|
#if SORTED_LONGNAME_MAXLEN != LONG_FILENAME_LENGTH
|
||||||
|
strncpy(sortnames[i], LONGEST_FILENAME, SORTED_LONGNAME_MAXLEN);
|
||||||
|
sortnames[i][SORTED_LONGNAME_MAXLEN - 1] = '\0';
|
||||||
|
#else
|
||||||
|
strncpy(sortnames[i], LONGEST_FILENAME, SORTED_LONGNAME_MAXLEN);
|
||||||
|
#endif
|
||||||
#if ENABLED(SDSORT_CACHE_NAMES)
|
#if ENABLED(SDSORT_CACHE_NAMES)
|
||||||
strcpy(sortshort[i], filename);
|
strcpy(sortshort[i], filename);
|
||||||
#endif
|
#endif
|
||||||
@@ -826,13 +827,22 @@ void CardReader::updir() {
|
|||||||
#if ENABLED(SDSORT_DYNAMIC_RAM)
|
#if ENABLED(SDSORT_DYNAMIC_RAM)
|
||||||
sortnames = new char*[1];
|
sortnames = new char*[1];
|
||||||
sortnames[0] = strdup(LONGEST_FILENAME); // malloc
|
sortnames[0] = strdup(LONGEST_FILENAME); // malloc
|
||||||
|
#if ENABLED(SDSORT_CACHE_NAMES)
|
||||||
sortshort = new char*[1];
|
sortshort = new char*[1];
|
||||||
sortshort[0] = strdup(filename); // malloc
|
sortshort[0] = strdup(filename); // malloc
|
||||||
|
#endif
|
||||||
isDir = new uint8_t[1];
|
isDir = new uint8_t[1];
|
||||||
#else
|
#else
|
||||||
strcpy(sortnames[0], LONGEST_FILENAME);
|
#if SORTED_LONGNAME_MAXLEN != LONG_FILENAME_LENGTH
|
||||||
|
strncpy(sortnames[0], LONGEST_FILENAME, SORTED_LONGNAME_MAXLEN);
|
||||||
|
sortnames[0][SORTED_LONGNAME_MAXLEN - 1] = '\0';
|
||||||
|
#else
|
||||||
|
strncpy(sortnames[0], LONGEST_FILENAME, SORTED_LONGNAME_MAXLEN);
|
||||||
|
#endif
|
||||||
|
#if ENABLED(SDSORT_CACHE_NAMES)
|
||||||
strcpy(sortshort[0], filename);
|
strcpy(sortshort[0], filename);
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
isDir[0] = filenameIsDir ? 0x01 : 0x00;
|
isDir[0] = filenameIsDir ? 0x01 : 0x00;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
@@ -860,6 +870,16 @@ void CardReader::updir() {
|
|||||||
|
|
||||||
#endif // SDCARD_SORT_ALPHA
|
#endif // SDCARD_SORT_ALPHA
|
||||||
|
|
||||||
|
uint16_t CardReader::get_num_Files() {
|
||||||
|
return
|
||||||
|
#if ENABLED(SDCARD_SORT_ALPHA) && SDSORT_USES_RAM && SDSORT_CACHE_NAMES
|
||||||
|
nrFiles // no need to access the SD card for filenames
|
||||||
|
#else
|
||||||
|
getnrfilenames()
|
||||||
|
#endif
|
||||||
|
;
|
||||||
|
}
|
||||||
|
|
||||||
void CardReader::printingHasFinished() {
|
void CardReader::printingHasFinished() {
|
||||||
stepper.synchronize();
|
stepper.synchronize();
|
||||||
file.close();
|
file.close();
|
||||||
@@ -879,6 +899,10 @@ void CardReader::printingHasFinished() {
|
|||||||
#if ENABLED(SDCARD_SORT_ALPHA)
|
#if ENABLED(SDCARD_SORT_ALPHA)
|
||||||
presort();
|
presort();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(SD_REPRINT_LAST_SELECTED_FILE)
|
||||||
|
lcd_reselect_last_file();
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -20,8 +20,8 @@
|
|||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef CARDREADER_H
|
#ifndef _CARDREADER_H_
|
||||||
#define CARDREADER_H
|
#define _CARDREADER_H_
|
||||||
|
|
||||||
#include "MarlinConfig.h"
|
#include "MarlinConfig.h"
|
||||||
|
|
||||||
@@ -30,7 +30,6 @@
|
|||||||
#define MAX_DIR_DEPTH 10 // Maximum folder depth
|
#define MAX_DIR_DEPTH 10 // Maximum folder depth
|
||||||
|
|
||||||
#include "SdFile.h"
|
#include "SdFile.h"
|
||||||
|
|
||||||
#include "types.h"
|
#include "types.h"
|
||||||
#include "enum.h"
|
#include "enum.h"
|
||||||
|
|
||||||
@@ -40,13 +39,15 @@ public:
|
|||||||
|
|
||||||
void initsd();
|
void initsd();
|
||||||
void write_command(char *buf);
|
void write_command(char *buf);
|
||||||
//files auto[0-9].g on the sd card are performed in a row
|
// Files auto[0-9].g on the sd card are performed in sequence.
|
||||||
//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 initialisation of
|
||||||
|
// the sd card to some seconds after the normal init, so the
|
||||||
|
// device is available soon after a reset.
|
||||||
|
|
||||||
void checkautostart(bool x);
|
void checkautostart(bool x);
|
||||||
void openFile(char* name, bool read, bool push_current=false);
|
void openFile(char* name, const bool read, const bool subcall=false);
|
||||||
void openLogFile(char* name);
|
void openLogFile(char* name);
|
||||||
void removeFile(char* name);
|
void removeFile(const char * const name);
|
||||||
void closefile(bool store_location=false);
|
void closefile(bool store_location=false);
|
||||||
void release();
|
void release();
|
||||||
void openAndPrintFile(const char *name);
|
void openAndPrintFile(const char *name);
|
||||||
@@ -66,9 +67,11 @@ public:
|
|||||||
|
|
||||||
void ls();
|
void ls();
|
||||||
void chdir(const char *relpath);
|
void chdir(const char *relpath);
|
||||||
void updir();
|
int8_t updir();
|
||||||
void setroot();
|
void setroot();
|
||||||
|
|
||||||
|
uint16_t get_num_Files();
|
||||||
|
|
||||||
#if ENABLED(SDCARD_SORT_ALPHA)
|
#if ENABLED(SDCARD_SORT_ALPHA)
|
||||||
void presort();
|
void presort();
|
||||||
void getfilename_sorted(const uint16_t nr);
|
void getfilename_sorted(const uint16_t nr);
|
||||||
@@ -111,6 +114,12 @@ private:
|
|||||||
uint8_t sort_order[SDSORT_LIMIT];
|
uint8_t sort_order[SDSORT_LIMIT];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(SDSORT_USES_RAM) && ENABLED(SDSORT_CACHE_NAMES) && DISABLED(SDSORT_DYNAMIC_RAM)
|
||||||
|
#define SORTED_LONGNAME_MAXLEN ((SDSORT_CACHE_VFATS) * (FILENAME_LENGTH) + 1)
|
||||||
|
#else
|
||||||
|
#define SORTED_LONGNAME_MAXLEN LONG_FILENAME_LENGTH
|
||||||
|
#endif
|
||||||
|
|
||||||
// Cache filenames to speed up SD menus.
|
// Cache filenames to speed up SD menus.
|
||||||
#if ENABLED(SDSORT_USES_RAM)
|
#if ENABLED(SDSORT_USES_RAM)
|
||||||
|
|
||||||
@@ -120,10 +129,10 @@ private:
|
|||||||
char **sortshort, **sortnames;
|
char **sortshort, **sortnames;
|
||||||
#else
|
#else
|
||||||
char sortshort[SDSORT_LIMIT][FILENAME_LENGTH];
|
char sortshort[SDSORT_LIMIT][FILENAME_LENGTH];
|
||||||
char sortnames[SDSORT_LIMIT][LONG_FILENAME_LENGTH];
|
char sortnames[SDSORT_LIMIT][SORTED_LONGNAME_MAXLEN];
|
||||||
#endif
|
#endif
|
||||||
#elif DISABLED(SDSORT_USES_STACK)
|
#elif DISABLED(SDSORT_USES_STACK)
|
||||||
char sortnames[SDSORT_LIMIT][LONG_FILENAME_LENGTH];
|
char sortnames[SDSORT_LIMIT][SORTED_LONGNAME_MAXLEN];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Folder sorting uses an isDir array when caching items.
|
// Folder sorting uses an isDir array when caching items.
|
||||||
@@ -148,8 +157,7 @@ private:
|
|||||||
uint8_t file_subcall_ctr;
|
uint8_t file_subcall_ctr;
|
||||||
uint32_t filespos[SD_PROCEDURE_DEPTH];
|
uint32_t filespos[SD_PROCEDURE_DEPTH];
|
||||||
char proc_filenames[SD_PROCEDURE_DEPTH][MAXPATHNAMELENGTH];
|
char proc_filenames[SD_PROCEDURE_DEPTH][MAXPATHNAMELENGTH];
|
||||||
uint32_t filesize;
|
uint32_t filesize, sdpos;
|
||||||
uint32_t sdpos;
|
|
||||||
|
|
||||||
millis_t next_autostart_ms;
|
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.
|
||||||
@@ -164,27 +172,27 @@ private:
|
|||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
extern CardReader card;
|
|
||||||
|
|
||||||
#define IS_SD_PRINTING (card.sdprinting)
|
|
||||||
#define IS_SD_FILE_OPEN (card.isFileOpen())
|
|
||||||
|
|
||||||
#if PIN_EXISTS(SD_DETECT)
|
#if PIN_EXISTS(SD_DETECT)
|
||||||
#if ENABLED(SD_DETECT_INVERTED)
|
#if ENABLED(SD_DETECT_INVERTED)
|
||||||
#define IS_SD_INSERTED (READ(SD_DETECT_PIN) != 0)
|
#define IS_SD_INSERTED (READ(SD_DETECT_PIN) == HIGH)
|
||||||
#else
|
#else
|
||||||
#define IS_SD_INSERTED (READ(SD_DETECT_PIN) == 0)
|
#define IS_SD_INSERTED (READ(SD_DETECT_PIN) == LOW)
|
||||||
#endif
|
#endif
|
||||||
#else
|
#else
|
||||||
//No card detect line? Assume the card is inserted.
|
// No card detect line? Assume the card is inserted.
|
||||||
#define IS_SD_INSERTED true
|
#define IS_SD_INSERTED true
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#else
|
extern CardReader card;
|
||||||
|
|
||||||
#define IS_SD_PRINTING (false)
|
|
||||||
#define IS_SD_FILE_OPEN (false)
|
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
#endif // __CARDREADER_H
|
#if ENABLED(SDSUPPORT)
|
||||||
|
#define IS_SD_PRINTING (card.sdprinting)
|
||||||
|
#define IS_SD_FILE_OPEN (card.isFileOpen())
|
||||||
|
#else
|
||||||
|
#define IS_SD_PRINTING (false)
|
||||||
|
#define IS_SD_FILE_OPEN (false)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // _CARDREADER_H_
|
||||||
|
|||||||
File diff suppressed because it is too large
Load Diff
@@ -52,10 +52,10 @@ class MarlinSettings {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if DISABLED(DISABLE_M503)
|
#if DISABLED(DISABLE_M503)
|
||||||
static void report(bool forReplay=false);
|
static void report(const bool forReplay=false);
|
||||||
#else
|
#else
|
||||||
FORCE_INLINE
|
FORCE_INLINE
|
||||||
static void report(bool forReplay=false) { UNUSED(forReplay); }
|
static void report(const bool forReplay=false) { UNUSED(forReplay); }
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|||||||
@@ -38,10 +38,8 @@
|
|||||||
#if ENABLED(START_BMPHIGH)
|
#if ENABLED(START_BMPHIGH)
|
||||||
#define START_BMPWIDTH 112
|
#define START_BMPWIDTH 112
|
||||||
#define START_BMPHEIGHT 38
|
#define START_BMPHEIGHT 38
|
||||||
#define START_BMPBYTEWIDTH 14
|
|
||||||
#define START_BMPBYTES 532 // START_BMPWIDTH * START_BMPHEIGHT / 8
|
|
||||||
|
|
||||||
const unsigned char start_bmp[START_BMPBYTES] PROGMEM = {
|
const unsigned char start_bmp[] PROGMEM = {
|
||||||
0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||||
0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||||
0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xFF, 0xFF,
|
0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xFF, 0xFF,
|
||||||
@@ -83,10 +81,8 @@
|
|||||||
#else
|
#else
|
||||||
#define START_BMPWIDTH 56
|
#define START_BMPWIDTH 56
|
||||||
#define START_BMPHEIGHT 19
|
#define START_BMPHEIGHT 19
|
||||||
#define START_BMPBYTEWIDTH 7
|
|
||||||
#define START_BMPBYTES 133 // START_BMPWIDTH * START_BMPHEIGHT / 8
|
|
||||||
|
|
||||||
const unsigned char start_bmp[START_BMPBYTES] PROGMEM = {
|
const unsigned char start_bmp[] PROGMEM = {
|
||||||
0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF,
|
||||||
0x60, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF,
|
0x60, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF,
|
||||||
0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF,
|
0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF,
|
||||||
@@ -115,12 +111,55 @@
|
|||||||
// When only one extruder is selected, the "1" on the symbol will not
|
// When only one extruder is selected, the "1" on the symbol will not
|
||||||
// be displayed.
|
// be displayed.
|
||||||
|
|
||||||
|
#define STATUS_SCREENWIDTH 115 // Width in pixels
|
||||||
|
#define STATUS_SCREENHEIGHT 19 // Height in pixels
|
||||||
|
|
||||||
#if HAS_TEMP_BED
|
#if HAS_TEMP_BED
|
||||||
#if HOTENDS == 1
|
#if HOTENDS == 0
|
||||||
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
const unsigned char status_screen0_bmp[] PROGMEM = {
|
||||||
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x0E, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x4F, 0x0F, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5F, 0x0F, 0xA0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5E, 0x07, 0xA0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x40, 0x60, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x40, 0xF0, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x40, 0xF0, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x40, 0x60, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x5E, 0x07, 0xA0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x5F, 0x0F, 0xA0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x4F, 0x0F, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x47, 0x0E, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x63, 0x0C, 0x60,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xE0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
|
||||||
|
};
|
||||||
|
const unsigned char status_screen1_bmp[] PROGMEM = {
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0xF8, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0xF0, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x60, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x58, 0x01, 0xA0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x5C, 0x63, 0xA0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x5E, 0xF7, 0xA0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x20, 0x82, 0x00, 0x5E, 0xF7, 0xA0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x5C, 0x63, 0xA0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x58, 0x01, 0xA0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x40, 0x60, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x04, 0x10, 0x00, 0x40, 0xF0, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x82, 0x08, 0x00, 0x41, 0xF8, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0x04, 0x00, 0x61, 0xF8, 0x60,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xE0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
|
||||||
|
};
|
||||||
|
#elif HOTENDS == 1
|
||||||
|
const unsigned char status_screen0_bmp[] PROGMEM = {
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
||||||
@@ -142,10 +181,7 @@
|
|||||||
0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
|
0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
|
||||||
};
|
};
|
||||||
|
|
||||||
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
const unsigned char status_screen1_bmp[] PROGMEM = {
|
||||||
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
|
||||||
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
|
||||||
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
||||||
@@ -167,10 +203,7 @@
|
|||||||
0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
|
0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
|
||||||
};
|
};
|
||||||
#elif HOTENDS == 2
|
#elif HOTENDS == 2
|
||||||
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
const unsigned char status_screen0_bmp[] PROGMEM = {
|
||||||
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
|
||||||
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
|
||||||
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
||||||
@@ -192,10 +225,7 @@
|
|||||||
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
|
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
|
||||||
};
|
};
|
||||||
|
|
||||||
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
const unsigned char status_screen1_bmp[] PROGMEM = {
|
||||||
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
|
||||||
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
|
||||||
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
||||||
@@ -217,10 +247,7 @@
|
|||||||
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
|
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
|
||||||
};
|
};
|
||||||
#else
|
#else
|
||||||
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
const unsigned char status_screen0_bmp[] PROGMEM = {
|
||||||
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
|
||||||
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
|
||||||
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
||||||
@@ -242,10 +269,7 @@
|
|||||||
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
|
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
|
||||||
};
|
};
|
||||||
|
|
||||||
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
const unsigned char status_screen1_bmp[] PROGMEM = {
|
||||||
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
|
||||||
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
|
||||||
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
||||||
@@ -266,13 +290,53 @@
|
|||||||
0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x0F, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xE0,
|
0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x0F, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xE0,
|
||||||
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
|
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00
|
||||||
};
|
};
|
||||||
#endif // Extruders
|
#endif // HOTENDS
|
||||||
#else
|
#else
|
||||||
#if HOTENDS == 1
|
#if HOTENDS == 0
|
||||||
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
const unsigned char status_screen0_bmp[] PROGMEM = {
|
||||||
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x0E, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x4F, 0x0F, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5F, 0x0F, 0xA0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5E, 0x07, 0xA0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x60, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0xF0, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0xF0, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x60, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5E, 0x07, 0xA0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5F, 0x0F, 0xA0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x4F, 0x0F, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x0E, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||||
|
};
|
||||||
|
const unsigned char status_screen1_bmp[] PROGMEM = {
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0xF8, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0xF0, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x60, 0x20,
|
||||||
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x58, 0x01, 0xA0,
|
||||||
|
0x7F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5C, 0x63, 0xA0,
|
||||||
|
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5E, 0xF7, 0xA0,
|
||||||
|
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5E, 0xF7, 0xA0,
|
||||||
|
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x5C, 0x63, 0xA0,
|
||||||
|
0x7F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x58, 0x01, 0xA0,
|
||||||
|
0x7F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x60, 0x20,
|
||||||
|
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0xF0, 0x20,
|
||||||
|
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x41, 0xF8, 0x20,
|
||||||
|
0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
||||||
|
0x3F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
|
0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
|
0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||||
|
};
|
||||||
|
#elif HOTENDS == 1
|
||||||
|
const unsigned char status_screen0_bmp[] PROGMEM = {
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
||||||
@@ -294,10 +358,7 @@
|
|||||||
0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||||
};
|
};
|
||||||
|
|
||||||
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
const unsigned char status_screen1_bmp[] PROGMEM = {
|
||||||
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
|
||||||
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
|
||||||
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
||||||
@@ -319,10 +380,7 @@
|
|||||||
0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||||
};
|
};
|
||||||
#elif HOTENDS == 2
|
#elif HOTENDS == 2
|
||||||
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
const unsigned char status_screen0_bmp[] PROGMEM = {
|
||||||
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
|
||||||
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
|
||||||
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
||||||
@@ -344,10 +402,7 @@
|
|||||||
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||||
};
|
};
|
||||||
|
|
||||||
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
const unsigned char status_screen1_bmp[] PROGMEM = {
|
||||||
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
|
||||||
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
|
||||||
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
||||||
@@ -369,10 +424,7 @@
|
|||||||
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||||
};
|
};
|
||||||
#else
|
#else
|
||||||
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
const unsigned char status_screen0_bmp[] PROGMEM = {
|
||||||
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
|
||||||
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
|
||||||
const unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x63, 0x0C, 0x60,
|
||||||
@@ -394,10 +446,7 @@
|
|||||||
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||||
};
|
};
|
||||||
|
|
||||||
#define STATUS_SCREENWIDTH 115 //Width in pixels
|
const unsigned char status_screen1_bmp[] PROGMEM = {
|
||||||
#define STATUS_SCREENHEIGHT 19 //Height in pixels
|
|
||||||
#define STATUS_SCREENBYTEWIDTH 15 //Width in bytes
|
|
||||||
const unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xE0,
|
||||||
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x61, 0xF8, 0x60,
|
||||||
@@ -418,85 +467,86 @@
|
|||||||
0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xE0,
|
||||||
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00
|
||||||
};
|
};
|
||||||
#endif // Extruders
|
#endif // HOTENDS
|
||||||
|
#endif // HAS_TEMP_BED
|
||||||
|
|
||||||
#if ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY)
|
#if ENABLED(BABYSTEP_ZPROBE_GFX_OVERLAY) || ENABLED(MESH_EDIT_GFX_OVERLAY)
|
||||||
const unsigned char cw_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
|
||||||
0x07,0xf8,0x00, // 000001111111100000000000
|
const unsigned char cw_bmp[] PROGMEM = {
|
||||||
0x0c,0x0c,0x00, // 000011000000110000000000
|
0x03,0xF8,0x00, // 000000111111100000000000
|
||||||
0x10,0x02,0x00, // 000100000000001000000000
|
0x0F,0xF7,0x00, // 000011111111111000000000
|
||||||
0x20,0x01,0x00, // 001000000000000100000000
|
0x17,0x0F,0x00, // 000111100000111100000000
|
||||||
0x60,0x01,0x80, // 011000000000000100000000
|
0x38,0x07,0x00, // 001110000000011100000000
|
||||||
0x40,0x00,0x80, // 010000000000000010000000
|
0x38,0x03,0x80, // 001110000000001110000000
|
||||||
0x40,0x03,0xe0, // 010000000000000011100000
|
0x70,0x03,0x80, // 011100000000001110000000
|
||||||
0x40,0x01,0xc0, // 010000000000000011000000
|
0x70,0x0F,0xE0, // 011100000000111111100000
|
||||||
0x40,0x00,0x80, // 010000000000000010000000
|
0x70,0x07,0xC0, // 011100000000011111000000
|
||||||
0x40,0x00,0x00, // 010000000000000000000000
|
0x70,0x03,0x80, // 011100000000001110000000
|
||||||
0x40,0x00,0x00, // 010000000000000000000000
|
0x70,0x01,0x00, // 011100000000000100000000
|
||||||
0x60,0x00,0x00, // 011000000000000000000000
|
0x70,0x00,0x00, // 011100000000000000000000
|
||||||
0x20,0x00,0x00, // 001000000000000000000000
|
0x68,0x00,0x00, // 001110000000000000000000
|
||||||
0x10,0x00,0x00, // 000100000000000000000000
|
0x38,0x07,0x00, // 001110000000011100000000
|
||||||
0x0c,0x0c,0x00, // 000011000000110000000000
|
0x17,0x0F,0x00, // 000111100000111100000000
|
||||||
0x07,0xf8,0x00 // 000001111111100000000000
|
0x0F,0xFE,0x00, // 000011111111111000000000
|
||||||
|
0x03,0xF8,0x00 // 000000111111100000000000
|
||||||
};
|
};
|
||||||
|
|
||||||
const unsigned char ccw_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
const unsigned char ccw_bmp[] PROGMEM = {
|
||||||
0x01,0xfe,0x00, // 000000011111111000000000
|
0x00,0xFE,0x00, // 000000001111111000000000
|
||||||
0x03,0x03,0x00, // 000000110000001100000000
|
0x03,0xFF,0x80, // 000000111111111110000000
|
||||||
0x04,0x00,0x80, // 000001000000000010000000
|
0x07,0x83,0xC0, // 000001111000001111000000
|
||||||
0x08,0x00,0x40, // 000010000000000001000000
|
0x0E,0x01,0xC0, // 000011100000000111000000
|
||||||
0x18,0x00,0x60, // 000110000000000001100000
|
0x0E,0x00,0xE0, // 000011100000000011100000
|
||||||
0x10,0x00,0x20, // 000100000000000000100000
|
0x1C,0x00,0xE0, // 000111000000000011100000
|
||||||
0x7c,0x00,0x20, // 011111000000000000100000
|
0x7F,0x00,0xE0, // 011111110000000011100000
|
||||||
0x38,0x00,0x20, // 001110000000000000100000
|
0x3E,0x00,0xE0, // 001111100000000011100000
|
||||||
0x10,0x00,0x20, // 000100000000000000100000
|
0x1C,0x00,0xE0, // 000111000000000011100000
|
||||||
0x00,0x00,0x20, // 000000000000000000100000
|
0x08,0x00,0xE0, // 000010000000000011100000
|
||||||
0x00,0x00,0x20, // 000000000000000000100000
|
0x00,0x00,0xE0, // 000000000000000011100000
|
||||||
0x00,0x00,0x60, // 000000000000000001100000
|
0x00,0x01,0xC0, // 000000000000000111000000
|
||||||
0x00,0x00,0x40, // 000000000000000001000000
|
0x0E,0x01,0xC0, // 000011100000000111000000
|
||||||
0x00,0x00,0x80, // 000000000000000010000000
|
0x0F,0x07,0x80, // 000011110000011110000000
|
||||||
0x03,0x03,0x00, // 000000110000001100000000
|
0x07,0xFF,0x00, // 000001111111111100000000
|
||||||
0x01,0xfe,0x00 // 000000011111111000000000
|
0x01,0xFC,0x00 // 000000011111110000000000
|
||||||
};
|
};
|
||||||
|
|
||||||
|
const unsigned char up_arrow_bmp[] PROGMEM = {
|
||||||
const unsigned char up_arrow_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
0x04,0x00, // 000001000000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x0F,0x00, // 000011110000
|
0x1F,0x00, // 000111110000
|
||||||
0x1F,0x80, // 000111111000
|
0x3F,0x80, // 001111111000
|
||||||
0x3F,0xC0, // 001111111100
|
0x7F,0xC0, // 011111111100
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00 // 000011100000
|
||||||
0x06,0x00 // 000001100000
|
|
||||||
};
|
};
|
||||||
|
|
||||||
const unsigned char down_arrow_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
const unsigned char down_arrow_bmp[] PROGMEM = {
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00, // 000001100000
|
0x7F,0xC0, // 011111111100
|
||||||
0x3F,0xC0, // 001111111100
|
0x3F,0x80, // 001111111000
|
||||||
0x1F,0x80, // 000111111000
|
0x1F,0x00, // 000111110000
|
||||||
0x0F,0x00, // 000011110000
|
0x0E,0x00, // 000011100000
|
||||||
0x06,0x00 // 000001100000
|
0x04,0x00 // 000001000000
|
||||||
};
|
};
|
||||||
|
|
||||||
const unsigned char offset_bedline_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
const unsigned char offset_bedline_bmp[] PROGMEM = {
|
||||||
0xFF,0xFF,0xFF // 111111111111111111111111
|
0xFF,0xFF,0xFF // 111111111111111111111111
|
||||||
};
|
};
|
||||||
|
|
||||||
const unsigned char nozzle_bmp[] PROGMEM = { //AVR-GCC, WinAVR
|
const unsigned char nozzle_bmp[] PROGMEM = {
|
||||||
0x7F,0x80, // 0111111110000000
|
0x7F,0x80, // 0111111110000000
|
||||||
0xFF,0xC0, // 1111111111000000
|
0xFF,0xC0, // 1111111111000000
|
||||||
0xFF,0xC0, // 1111111111000000
|
0xFF,0xC0, // 1111111111000000
|
||||||
@@ -510,5 +560,4 @@
|
|||||||
0x1E,0x00, // 0001111000000000
|
0x1E,0x00, // 0001111000000000
|
||||||
0x0C,0x00 // 0000110000000000
|
0x0C,0x00 // 0000110000000000
|
||||||
};
|
};
|
||||||
#endif // BABYSTEP_ZPROBE_GFX_OVERLAY
|
#endif // BABYSTEP_ZPROBE_GFX_OVERLAY || MESH_EDIT_GFX_OVERLAY
|
||||||
#endif // HAS_TEMP_BED
|
|
||||||
|
|||||||
@@ -32,7 +32,93 @@
|
|||||||
Max Font ascent = 8 descent=-1
|
Max Font ascent = 8 descent=-1
|
||||||
*/
|
*/
|
||||||
#include <U8glib.h>
|
#include <U8glib.h>
|
||||||
const u8g_fntpgm_uint8_t ISO10646_1_5x7[2592] U8G_SECTION(".progmem.ISO10646_1_5x7") = {
|
|
||||||
|
#if defined(__AVR__) && ENABLED(NOT_EXTENDED_ISO10646_1_5X7)
|
||||||
|
|
||||||
|
//
|
||||||
|
// Reduced font (only symbols 32 - 127) - About 1400 bytes smaller
|
||||||
|
//
|
||||||
|
const u8g_fntpgm_uint8_t ISO10646_1_5x7[] U8G_SECTION(".progmem.ISO10646_1_5x7") = {
|
||||||
|
0,6,9,0,254,7,1,146,3,33,32,127,255,7,255,7,
|
||||||
|
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,
|
||||||
|
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,
|
||||||
|
64,152,24,5,7,7,6,0,0,96,144,160,64,168,144,104,
|
||||||
|
2,3,3,6,1,4,192,64,128,3,7,7,6,1,0,32,
|
||||||
|
64,128,128,128,64,32,3,7,7,6,1,0,128,64,32,32,
|
||||||
|
32,64,128,5,5,5,6,0,1,32,168,112,168,32,5,5,
|
||||||
|
5,6,0,1,32,32,248,32,32,2,3,3,6,2,255,192,
|
||||||
|
64,128,5,1,1,6,0,3,248,2,2,2,6,2,0,192,
|
||||||
|
192,5,5,5,6,0,1,8,16,32,64,128,5,7,7,6,
|
||||||
|
0,0,112,136,136,136,136,136,112,3,7,7,6,1,0,64,
|
||||||
|
192,64,64,64,64,224,5,7,7,6,0,0,112,136,8,112,
|
||||||
|
128,128,248,5,7,7,6,0,0,248,16,32,16,8,8,240,
|
||||||
|
5,7,7,6,0,0,16,48,80,144,248,16,16,5,7,7,
|
||||||
|
6,0,0,248,128,240,8,8,136,112,5,7,7,6,0,0,
|
||||||
|
112,128,128,240,136,136,112,5,7,7,6,0,0,248,8,16,
|
||||||
|
32,32,32,32,5,7,7,6,0,0,112,136,136,112,136,136,
|
||||||
|
112,5,7,7,6,0,0,112,136,136,120,8,8,112,2,5,
|
||||||
|
5,6,2,0,192,192,0,192,192,2,6,6,6,2,255,192,
|
||||||
|
192,0,192,64,128,4,7,7,6,0,0,16,32,64,128,64,
|
||||||
|
32,16,5,3,3,6,0,2,248,0,248,4,7,7,6,1,
|
||||||
|
0,128,64,32,16,32,64,128,5,7,7,6,0,0,112,136,
|
||||||
|
8,16,32,0,32,5,7,7,6,0,0,112,136,8,104,168,
|
||||||
|
168,112,5,7,7,6,0,0,112,136,136,248,136,136,136,5,
|
||||||
|
7,7,6,0,0,240,136,136,240,136,136,240,5,7,7,6,
|
||||||
|
0,0,112,136,128,128,128,136,112,5,7,7,6,0,0,240,
|
||||||
|
136,136,136,136,136,240,5,7,7,6,0,0,248,128,128,240,
|
||||||
|
128,128,248,5,7,7,6,0,0,248,128,128,240,128,128,128,
|
||||||
|
5,7,7,6,0,0,112,136,128,184,136,136,112,5,7,7,
|
||||||
|
6,0,0,136,136,136,248,136,136,136,1,7,7,6,2,0,
|
||||||
|
128,128,128,128,128,128,128,5,7,7,6,0,0,56,16,16,
|
||||||
|
16,16,144,96,5,7,7,6,0,0,136,144,160,192,160,144,
|
||||||
|
136,5,7,7,6,0,0,128,128,128,128,128,128,248,5,7,
|
||||||
|
7,6,0,0,136,216,168,136,136,136,136,5,7,7,6,0,
|
||||||
|
0,136,136,200,168,152,136,136,5,7,7,6,0,0,112,136,
|
||||||
|
136,136,136,136,112,5,7,7,6,0,0,240,136,136,240,128,
|
||||||
|
128,128,5,7,7,6,0,0,112,136,136,136,168,144,104,5,
|
||||||
|
7,7,6,0,0,240,136,136,240,160,144,136,5,7,7,6,
|
||||||
|
0,0,120,128,128,112,8,8,240,5,7,7,6,0,0,248,
|
||||||
|
32,32,32,32,32,32,5,7,7,6,0,0,136,136,136,136,
|
||||||
|
136,136,112,5,7,7,6,0,0,136,136,136,136,136,80,32,
|
||||||
|
5,7,7,6,0,0,136,136,136,136,136,168,80,5,7,7,
|
||||||
|
6,0,0,136,136,80,32,80,136,136,5,7,7,6,0,0,
|
||||||
|
136,136,136,80,32,32,32,5,7,7,6,0,0,248,8,16,
|
||||||
|
32,64,128,248,3,7,7,6,1,0,224,128,128,128,128,128,
|
||||||
|
224,5,5,5,6,0,1,128,64,32,16,8,3,7,7,6,
|
||||||
|
1,0,224,32,32,32,32,32,224,5,3,3,6,0,4,32,
|
||||||
|
80,136,5,1,1,6,0,0,248,2,2,2,6,2,5,128,
|
||||||
|
64,5,5,5,6,0,0,112,8,120,136,120,5,7,7,6,
|
||||||
|
0,0,128,128,176,200,136,136,240,5,5,5,6,0,0,112,
|
||||||
|
128,128,136,112,5,7,7,6,0,0,8,8,104,152,136,136,
|
||||||
|
120,5,5,5,6,0,0,112,136,248,128,112,5,7,7,6,
|
||||||
|
0,0,48,72,224,64,64,64,64,5,6,6,6,0,255,112,
|
||||||
|
136,136,120,8,112,5,7,7,6,0,0,128,128,176,200,136,
|
||||||
|
136,136,1,7,7,6,2,0,128,0,128,128,128,128,128,3,
|
||||||
|
8,8,6,1,255,32,0,32,32,32,32,160,64,4,7,7,
|
||||||
|
6,0,0,128,128,144,160,192,160,144,3,7,7,6,1,0,
|
||||||
|
192,64,64,64,64,64,224,5,5,5,6,0,0,208,168,168,
|
||||||
|
168,168,5,5,5,6,0,0,176,200,136,136,136,5,5,5,
|
||||||
|
6,0,0,112,136,136,136,112,5,6,6,6,0,255,240,136,
|
||||||
|
136,240,128,128,5,6,6,6,0,255,120,136,136,120,8,8,
|
||||||
|
5,5,5,6,0,0,176,200,128,128,128,5,5,5,6,0,
|
||||||
|
0,112,128,112,8,240,4,7,7,6,0,0,64,64,224,64,
|
||||||
|
64,64,48,5,5,5,6,0,0,136,136,136,152,104,5,5,
|
||||||
|
5,6,0,0,136,136,136,80,32,5,5,5,6,0,0,136,
|
||||||
|
136,168,168,80,5,5,5,6,0,0,136,80,32,80,136,5,
|
||||||
|
6,6,6,0,255,136,136,136,120,8,112,5,5,5,6,0,
|
||||||
|
0,248,16,32,64,248,3,7,7,6,1,0,32,64,64,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,2,2,
|
||||||
|
6,0,2,104,144,0,0,0,6,0,0};
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
//
|
||||||
|
// Extended (original) font (symbols 32 - 255)
|
||||||
|
//
|
||||||
|
const u8g_fntpgm_uint8_t ISO10646_1_5x7[] U8G_SECTION(".progmem.ISO10646_1_5x7") = {
|
||||||
0, 6, 9, 0, 254, 7, 1, 146, 3, 33, 32, 255, 255, 8, 255, 7,
|
0, 6, 9, 0, 254, 7, 1, 146, 3, 33, 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,
|
||||||
@@ -195,4 +281,6 @@ const u8g_fntpgm_uint8_t ISO10646_1_5x7[2592] U8G_SECTION(".progmem.ISO10646_1_5
|
|||||||
0, 136, 136, 136, 152, 104, 5, 9, 9, 6, 0, 255, 16, 32, 0, 136,
|
0, 136, 136, 136, 152, 104, 5, 9, 9, 6, 0, 255, 16, 32, 0, 136,
|
||||||
136, 136, 248, 8, 112, 4, 7, 7, 6, 1, 255, 192, 64, 96, 80, 96,
|
136, 136, 248, 8, 112, 4, 7, 7, 6, 1, 255, 192, 64, 96, 80, 96,
|
||||||
64, 224, 5, 8, 8, 6, 0, 255, 80, 0, 136, 136, 136, 120, 8, 112
|
64, 224, 5, 8, 8, 6, 0, 255, 80, 0, 136, 136, 136, 120, 8, 112
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|||||||
@@ -111,7 +111,7 @@ void endstop_ISR(void) { endstop_ISR_worker(); }
|
|||||||
void setup_endstop_interrupts( void ) {
|
void setup_endstop_interrupts( void ) {
|
||||||
|
|
||||||
#if HAS_X_MAX
|
#if HAS_X_MAX
|
||||||
#if (digitalPinToInterrupt(X_MAX_PIN) != NOT_AN_INTERRUPT) // if pin has an external interrupt
|
#if digitalPinToInterrupt(X_MAX_PIN) != NOT_AN_INTERRUPT // if pin has an external interrupt
|
||||||
attachInterrupt(digitalPinToInterrupt(X_MAX_PIN), endstop_ISR, CHANGE); // assign it
|
attachInterrupt(digitalPinToInterrupt(X_MAX_PIN), endstop_ISR, CHANGE); // assign it
|
||||||
#else
|
#else
|
||||||
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
||||||
@@ -121,7 +121,7 @@ void setup_endstop_interrupts( void ) {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_X_MIN
|
#if HAS_X_MIN
|
||||||
#if (digitalPinToInterrupt(X_MIN_PIN) != NOT_AN_INTERRUPT)
|
#if digitalPinToInterrupt(X_MIN_PIN) != NOT_AN_INTERRUPT
|
||||||
attachInterrupt(digitalPinToInterrupt(X_MIN_PIN), endstop_ISR, CHANGE);
|
attachInterrupt(digitalPinToInterrupt(X_MIN_PIN), endstop_ISR, CHANGE);
|
||||||
#else
|
#else
|
||||||
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
||||||
@@ -131,7 +131,7 @@ void setup_endstop_interrupts( void ) {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_Y_MAX
|
#if HAS_Y_MAX
|
||||||
#if (digitalPinToInterrupt(Y_MAX_PIN) != NOT_AN_INTERRUPT)
|
#if digitalPinToInterrupt(Y_MAX_PIN) != NOT_AN_INTERRUPT
|
||||||
attachInterrupt(digitalPinToInterrupt(Y_MAX_PIN), endstop_ISR, CHANGE);
|
attachInterrupt(digitalPinToInterrupt(Y_MAX_PIN), endstop_ISR, CHANGE);
|
||||||
#else
|
#else
|
||||||
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
||||||
@@ -141,7 +141,7 @@ void setup_endstop_interrupts( void ) {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_Y_MIN
|
#if HAS_Y_MIN
|
||||||
#if (digitalPinToInterrupt(Y_MIN_PIN) != NOT_AN_INTERRUPT)
|
#if digitalPinToInterrupt(Y_MIN_PIN) != NOT_AN_INTERRUPT
|
||||||
attachInterrupt(digitalPinToInterrupt(Y_MIN_PIN), endstop_ISR, CHANGE);
|
attachInterrupt(digitalPinToInterrupt(Y_MIN_PIN), endstop_ISR, CHANGE);
|
||||||
#else
|
#else
|
||||||
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
||||||
@@ -151,7 +151,7 @@ void setup_endstop_interrupts( void ) {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_Z_MAX
|
#if HAS_Z_MAX
|
||||||
#if (digitalPinToInterrupt(Z_MAX_PIN) != NOT_AN_INTERRUPT)
|
#if digitalPinToInterrupt(Z_MAX_PIN) != NOT_AN_INTERRUPT
|
||||||
attachInterrupt(digitalPinToInterrupt(Z_MAX_PIN), endstop_ISR, CHANGE);
|
attachInterrupt(digitalPinToInterrupt(Z_MAX_PIN), endstop_ISR, CHANGE);
|
||||||
#else
|
#else
|
||||||
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
||||||
@@ -161,7 +161,7 @@ void setup_endstop_interrupts( void ) {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_Z_MIN
|
#if HAS_Z_MIN
|
||||||
#if (digitalPinToInterrupt(Z_MIN_PIN) != NOT_AN_INTERRUPT)
|
#if digitalPinToInterrupt(Z_MIN_PIN) != NOT_AN_INTERRUPT
|
||||||
attachInterrupt(digitalPinToInterrupt(Z_MIN_PIN), endstop_ISR, CHANGE);
|
attachInterrupt(digitalPinToInterrupt(Z_MIN_PIN), endstop_ISR, CHANGE);
|
||||||
#else
|
#else
|
||||||
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
||||||
@@ -170,8 +170,48 @@ void setup_endstop_interrupts( void ) {
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_X2_MAX
|
||||||
|
#if (digitalPinToInterrupt(X2_MAX_PIN) != NOT_AN_INTERRUPT)
|
||||||
|
attachInterrupt(digitalPinToInterrupt(X2_MAX_PIN), endstop_ISR, CHANGE);
|
||||||
|
#else
|
||||||
|
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
||||||
|
static_assert(digitalPinToPCICR(X2_MAX_PIN) != NULL, "X2_MAX_PIN is not interrupt-capable");
|
||||||
|
pciSetup(X2_MAX_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_X2_MIN
|
||||||
|
#if (digitalPinToInterrupt(X2_MIN_PIN) != NOT_AN_INTERRUPT)
|
||||||
|
attachInterrupt(digitalPinToInterrupt(X2_MIN_PIN), endstop_ISR, CHANGE);
|
||||||
|
#else
|
||||||
|
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
||||||
|
static_assert(digitalPinToPCICR(X2_MIN_PIN) != NULL, "X2_MIN_PIN is not interrupt-capable");
|
||||||
|
pciSetup(X2_MIN_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_Y2_MAX
|
||||||
|
#if (digitalPinToInterrupt(Y2_MAX_PIN) != NOT_AN_INTERRUPT)
|
||||||
|
attachInterrupt(digitalPinToInterrupt(Y2_MAX_PIN), endstop_ISR, CHANGE);
|
||||||
|
#else
|
||||||
|
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
||||||
|
static_assert(digitalPinToPCICR(Y2_MAX_PIN) != NULL, "Y2_MAX_PIN is not interrupt-capable");
|
||||||
|
pciSetup(Y2_MAX_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_Y2_MIN
|
||||||
|
#if (digitalPinToInterrupt(Y2_MIN_PIN) != NOT_AN_INTERRUPT)
|
||||||
|
attachInterrupt(digitalPinToInterrupt(Y2_MIN_PIN), endstop_ISR, CHANGE);
|
||||||
|
#else
|
||||||
|
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
||||||
|
static_assert(digitalPinToPCICR(Y2_MIN_PIN) != NULL, "Y2_MIN_PIN is not interrupt-capable");
|
||||||
|
pciSetup(Y2_MIN_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAS_Z2_MAX
|
#if HAS_Z2_MAX
|
||||||
#if (digitalPinToInterrupt(Z2_MAX_PIN) != NOT_AN_INTERRUPT)
|
#if digitalPinToInterrupt(Z2_MAX_PIN) != NOT_AN_INTERRUPT
|
||||||
attachInterrupt(digitalPinToInterrupt(Z2_MAX_PIN), endstop_ISR, CHANGE);
|
attachInterrupt(digitalPinToInterrupt(Z2_MAX_PIN), endstop_ISR, CHANGE);
|
||||||
#else
|
#else
|
||||||
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
||||||
@@ -181,7 +221,7 @@ void setup_endstop_interrupts( void ) {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_Z2_MIN
|
#if HAS_Z2_MIN
|
||||||
#if (digitalPinToInterrupt(Z2_MIN_PIN) != NOT_AN_INTERRUPT)
|
#if digitalPinToInterrupt(Z2_MIN_PIN) != NOT_AN_INTERRUPT
|
||||||
attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
|
attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
|
||||||
#else
|
#else
|
||||||
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
||||||
@@ -191,7 +231,7 @@ void setup_endstop_interrupts( void ) {
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_Z_MIN_PROBE_PIN
|
#if HAS_Z_MIN_PROBE_PIN
|
||||||
#if (digitalPinToInterrupt(Z_MIN_PROBE_PIN) != NOT_AN_INTERRUPT)
|
#if digitalPinToInterrupt(Z_MIN_PROBE_PIN) != NOT_AN_INTERRUPT
|
||||||
attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
|
attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
|
||||||
#else
|
#else
|
||||||
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
|
||||||
|
|||||||
@@ -41,7 +41,7 @@ Endstops endstops;
|
|||||||
bool Endstops::enabled, Endstops::enabled_globally; // Initialized by settings.load()
|
bool Endstops::enabled, Endstops::enabled_globally; // Initialized by settings.load()
|
||||||
volatile char Endstops::endstop_hit_bits; // use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT value
|
volatile char Endstops::endstop_hit_bits; // use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT value
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
uint16_t
|
uint16_t
|
||||||
#else
|
#else
|
||||||
byte
|
byte
|
||||||
@@ -67,6 +67,14 @@ void Endstops::init() {
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_X2_MIN
|
||||||
|
#if ENABLED(ENDSTOPPULLUP_XMIN)
|
||||||
|
SET_INPUT_PULLUP(X2_MIN_PIN);
|
||||||
|
#else
|
||||||
|
SET_INPUT(X2_MIN_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAS_Y_MIN
|
#if HAS_Y_MIN
|
||||||
#if ENABLED(ENDSTOPPULLUP_YMIN)
|
#if ENABLED(ENDSTOPPULLUP_YMIN)
|
||||||
SET_INPUT_PULLUP(Y_MIN_PIN);
|
SET_INPUT_PULLUP(Y_MIN_PIN);
|
||||||
@@ -75,6 +83,14 @@ void Endstops::init() {
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_Y2_MIN
|
||||||
|
#if ENABLED(ENDSTOPPULLUP_YMIN)
|
||||||
|
SET_INPUT_PULLUP(Y2_MIN_PIN);
|
||||||
|
#else
|
||||||
|
SET_INPUT(Y2_MIN_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAS_Z_MIN
|
#if HAS_Z_MIN
|
||||||
#if ENABLED(ENDSTOPPULLUP_ZMIN)
|
#if ENABLED(ENDSTOPPULLUP_ZMIN)
|
||||||
SET_INPUT_PULLUP(Z_MIN_PIN);
|
SET_INPUT_PULLUP(Z_MIN_PIN);
|
||||||
@@ -99,6 +115,14 @@ void Endstops::init() {
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_X2_MAX
|
||||||
|
#if ENABLED(ENDSTOPPULLUP_XMAX)
|
||||||
|
SET_INPUT_PULLUP(X2_MAX_PIN);
|
||||||
|
#else
|
||||||
|
SET_INPUT(X2_MAX_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAS_Y_MAX
|
#if HAS_Y_MAX
|
||||||
#if ENABLED(ENDSTOPPULLUP_YMAX)
|
#if ENABLED(ENDSTOPPULLUP_YMAX)
|
||||||
SET_INPUT_PULLUP(Y_MAX_PIN);
|
SET_INPUT_PULLUP(Y_MAX_PIN);
|
||||||
@@ -107,6 +131,14 @@ void Endstops::init() {
|
|||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_Y2_MAX
|
||||||
|
#if ENABLED(ENDSTOPPULLUP_YMAX)
|
||||||
|
SET_INPUT_PULLUP(Y2_MAX_PIN);
|
||||||
|
#else
|
||||||
|
SET_INPUT(Y2_MAX_PIN);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAS_Z_MAX
|
#if HAS_Z_MAX
|
||||||
#if ENABLED(ENDSTOPPULLUP_ZMAX)
|
#if ENABLED(ENDSTOPPULLUP_ZMAX)
|
||||||
SET_INPUT_PULLUP(Z_MAX_PIN);
|
SET_INPUT_PULLUP(Z_MAX_PIN);
|
||||||
@@ -185,37 +217,45 @@ void Endstops::report_state() {
|
|||||||
|
|
||||||
void Endstops::M119() {
|
void Endstops::M119() {
|
||||||
SERIAL_PROTOCOLLNPGM(MSG_M119_REPORT);
|
SERIAL_PROTOCOLLNPGM(MSG_M119_REPORT);
|
||||||
|
#define ES_REPORT(AXIS) do{ \
|
||||||
|
SERIAL_PROTOCOLPGM(MSG_##AXIS); \
|
||||||
|
SERIAL_PROTOCOLLN(((READ(AXIS##_PIN)^AXIS##_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN)); \
|
||||||
|
}while(0)
|
||||||
#if HAS_X_MIN
|
#if HAS_X_MIN
|
||||||
SERIAL_PROTOCOLPGM(MSG_X_MIN);
|
ES_REPORT(X_MIN);
|
||||||
SERIAL_PROTOCOLLN(((READ(X_MIN_PIN)^X_MIN_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
|
#endif
|
||||||
|
#if HAS_X2_MIN
|
||||||
|
ES_REPORT(X2_MIN);
|
||||||
#endif
|
#endif
|
||||||
#if HAS_X_MAX
|
#if HAS_X_MAX
|
||||||
SERIAL_PROTOCOLPGM(MSG_X_MAX);
|
ES_REPORT(X_MAX);
|
||||||
SERIAL_PROTOCOLLN(((READ(X_MAX_PIN)^X_MAX_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
|
#endif
|
||||||
|
#if HAS_X2_MAX
|
||||||
|
ES_REPORT(X2_MAX);
|
||||||
#endif
|
#endif
|
||||||
#if HAS_Y_MIN
|
#if HAS_Y_MIN
|
||||||
SERIAL_PROTOCOLPGM(MSG_Y_MIN);
|
ES_REPORT(Y_MIN);
|
||||||
SERIAL_PROTOCOLLN(((READ(Y_MIN_PIN)^Y_MIN_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
|
#endif
|
||||||
|
#if HAS_Y2_MIN
|
||||||
|
ES_REPORT(Y2_MIN);
|
||||||
#endif
|
#endif
|
||||||
#if HAS_Y_MAX
|
#if HAS_Y_MAX
|
||||||
SERIAL_PROTOCOLPGM(MSG_Y_MAX);
|
ES_REPORT(Y_MAX);
|
||||||
SERIAL_PROTOCOLLN(((READ(Y_MAX_PIN)^Y_MAX_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
|
#endif
|
||||||
|
#if HAS_Y2_MAX
|
||||||
|
ES_REPORT(Y2_MAX);
|
||||||
#endif
|
#endif
|
||||||
#if HAS_Z_MIN
|
#if HAS_Z_MIN
|
||||||
SERIAL_PROTOCOLPGM(MSG_Z_MIN);
|
ES_REPORT(Z_MIN);
|
||||||
SERIAL_PROTOCOLLN(((READ(Z_MIN_PIN)^Z_MIN_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
|
|
||||||
#endif
|
#endif
|
||||||
#if HAS_Z2_MIN
|
#if HAS_Z2_MIN
|
||||||
SERIAL_PROTOCOLPGM(MSG_Z2_MIN);
|
ES_REPORT(Z2_MIN);
|
||||||
SERIAL_PROTOCOLLN(((READ(Z2_MIN_PIN)^Z2_MIN_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
|
|
||||||
#endif
|
#endif
|
||||||
#if HAS_Z_MAX
|
#if HAS_Z_MAX
|
||||||
SERIAL_PROTOCOLPGM(MSG_Z_MAX);
|
ES_REPORT(Z_MAX);
|
||||||
SERIAL_PROTOCOLLN(((READ(Z_MAX_PIN)^Z_MAX_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
|
|
||||||
#endif
|
#endif
|
||||||
#if HAS_Z2_MAX
|
#if HAS_Z2_MAX
|
||||||
SERIAL_PROTOCOLPGM(MSG_Z2_MAX);
|
ES_REPORT(Z2_MAX);
|
||||||
SERIAL_PROTOCOLLN(((READ(Z2_MAX_PIN)^Z2_MAX_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
|
|
||||||
#endif
|
#endif
|
||||||
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
|
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
|
||||||
SERIAL_PROTOCOLPGM(MSG_Z_PROBE);
|
SERIAL_PROTOCOLPGM(MSG_Z_PROBE);
|
||||||
@@ -227,9 +267,27 @@ void Endstops::M119() {
|
|||||||
#endif
|
#endif
|
||||||
} // Endstops::M119
|
} // Endstops::M119
|
||||||
|
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
void Endstops::test_dual_x_endstops(const EndstopEnum es1, const EndstopEnum es2) {
|
||||||
|
byte x_test = TEST_ENDSTOP(es1) | (TEST_ENDSTOP(es2) << 1); // bit 0 for X, bit 1 for X2
|
||||||
|
if (x_test && stepper.current_block->steps[X_AXIS] > 0) {
|
||||||
|
SBI(endstop_hit_bits, X_MIN);
|
||||||
|
if (!stepper.performing_homing || (x_test == 0x3)) //if not performing home or if both endstops were trigged during homing...
|
||||||
|
stepper.kill_current_block();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
void Endstops::test_dual_y_endstops(const EndstopEnum es1, const EndstopEnum es2) {
|
||||||
|
byte y_test = TEST_ENDSTOP(es1) | (TEST_ENDSTOP(es2) << 1); // bit 0 for Y, bit 1 for Y2
|
||||||
|
if (y_test && stepper.current_block->steps[Y_AXIS] > 0) {
|
||||||
|
SBI(endstop_hit_bits, Y_MIN);
|
||||||
|
if (!stepper.performing_homing || (y_test == 0x3)) //if not performing home or if both endstops were trigged during homing...
|
||||||
|
stepper.kill_current_block();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
|
|
||||||
// Pass the result of the endstop test
|
|
||||||
void Endstops::test_dual_z_endstops(const EndstopEnum es1, const EndstopEnum es2) {
|
void Endstops::test_dual_z_endstops(const EndstopEnum es1, const EndstopEnum es2) {
|
||||||
byte z_test = TEST_ENDSTOP(es1) | (TEST_ENDSTOP(es2) << 1); // bit 0 for Z, bit 1 for Z2
|
byte z_test = TEST_ENDSTOP(es1) | (TEST_ENDSTOP(es2) << 1); // bit 0 for Z, bit 1 for Z2
|
||||||
if (z_test && stepper.current_block->steps[Z_AXIS] > 0) {
|
if (z_test && stepper.current_block->steps[Z_AXIS] > 0) {
|
||||||
@@ -238,7 +296,6 @@ void Endstops::M119() {
|
|||||||
stepper.kill_current_block();
|
stepper.kill_current_block();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Check endstops - Called from ISR!
|
// Check endstops - Called from ISR!
|
||||||
@@ -260,7 +317,7 @@ void Endstops::update() {
|
|||||||
_ENDSTOP_HIT(AXIS, MINMAX); \
|
_ENDSTOP_HIT(AXIS, MINMAX); \
|
||||||
stepper.endstop_triggered(_AXIS(AXIS)); \
|
stepper.endstop_triggered(_AXIS(AXIS)); \
|
||||||
} \
|
} \
|
||||||
} while(0)
|
}while(0)
|
||||||
|
|
||||||
#if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && !(CORE_IS_XY || CORE_IS_XZ)
|
#if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && !(CORE_IS_XY || CORE_IS_XZ)
|
||||||
// If G38 command is active check Z_MIN_PROBE for ALL movement
|
// If G38 command is active check Z_MIN_PROBE for ALL movement
|
||||||
@@ -357,18 +414,36 @@ void Endstops::update() {
|
|||||||
/**
|
/**
|
||||||
* Check and update endstops according to conditions
|
* Check and update endstops according to conditions
|
||||||
*/
|
*/
|
||||||
|
|
||||||
if (X_MOVE_TEST) {
|
if (X_MOVE_TEST) {
|
||||||
if (stepper.motor_direction(X_AXIS_HEAD)) {
|
if (stepper.motor_direction(X_AXIS_HEAD)) { // -direction
|
||||||
if (X_MIN_TEST) { // -direction
|
|
||||||
#if HAS_X_MIN
|
#if HAS_X_MIN
|
||||||
UPDATE_ENDSTOP(X, MIN);
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
UPDATE_ENDSTOP_BIT(X, MIN);
|
||||||
|
#if HAS_X2_MIN
|
||||||
|
UPDATE_ENDSTOP_BIT(X2, MIN);
|
||||||
|
#else
|
||||||
|
COPY_BIT(current_endstop_bits, X_MIN, X2_MIN);
|
||||||
|
#endif
|
||||||
|
test_dual_x_endstops(X_MIN, X2_MIN);
|
||||||
|
#else
|
||||||
|
if (X_MIN_TEST) UPDATE_ENDSTOP(X, MIN);
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
else { // +direction
|
||||||
else if (X_MAX_TEST) { // +direction
|
|
||||||
#if HAS_X_MAX
|
#if HAS_X_MAX
|
||||||
UPDATE_ENDSTOP(X, MAX);
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
UPDATE_ENDSTOP_BIT(X, MAX);
|
||||||
|
#if HAS_X2_MAX
|
||||||
|
UPDATE_ENDSTOP_BIT(X2, MAX);
|
||||||
|
#else
|
||||||
|
COPY_BIT(current_endstop_bits, X_MAX, X2_MAX);
|
||||||
|
#endif
|
||||||
|
test_dual_x_endstops(X_MAX, X2_MAX);
|
||||||
|
#else
|
||||||
|
if (X_MIN_TEST) UPDATE_ENDSTOP(X, MAX);
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -376,13 +451,33 @@ void Endstops::update() {
|
|||||||
if (Y_MOVE_TEST) {
|
if (Y_MOVE_TEST) {
|
||||||
if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction
|
if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction
|
||||||
#if HAS_Y_MIN
|
#if HAS_Y_MIN
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
UPDATE_ENDSTOP_BIT(Y, MIN);
|
||||||
|
#if HAS_Y2_MIN
|
||||||
|
UPDATE_ENDSTOP_BIT(Y2, MIN);
|
||||||
|
#else
|
||||||
|
COPY_BIT(current_endstop_bits, Y_MIN, Y2_MIN);
|
||||||
|
#endif
|
||||||
|
test_dual_y_endstops(Y_MIN, Y2_MIN);
|
||||||
|
#else
|
||||||
UPDATE_ENDSTOP(Y, MIN);
|
UPDATE_ENDSTOP(Y, MIN);
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
else { // +direction
|
else { // +direction
|
||||||
#if HAS_Y_MAX
|
#if HAS_Y_MAX
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
UPDATE_ENDSTOP_BIT(Y, MAX);
|
||||||
|
#if HAS_Y2_MAX
|
||||||
|
UPDATE_ENDSTOP_BIT(Y2, MAX);
|
||||||
|
#else
|
||||||
|
COPY_BIT(current_endstop_bits, Y_MAX, Y2_MAX);
|
||||||
|
#endif
|
||||||
|
test_dual_y_endstops(Y_MAX, Y2_MAX);
|
||||||
|
#else
|
||||||
UPDATE_ENDSTOP(Y, MAX);
|
UPDATE_ENDSTOP(Y, MAX);
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -390,27 +485,21 @@ void Endstops::update() {
|
|||||||
if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up.
|
if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up.
|
||||||
#if HAS_Z_MIN
|
#if HAS_Z_MIN
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
|
|
||||||
UPDATE_ENDSTOP_BIT(Z, MIN);
|
UPDATE_ENDSTOP_BIT(Z, MIN);
|
||||||
#if HAS_Z2_MIN
|
#if HAS_Z2_MIN
|
||||||
UPDATE_ENDSTOP_BIT(Z2, MIN);
|
UPDATE_ENDSTOP_BIT(Z2, MIN);
|
||||||
#else
|
#else
|
||||||
COPY_BIT(current_endstop_bits, Z_MIN, Z2_MIN);
|
COPY_BIT(current_endstop_bits, Z_MIN, Z2_MIN);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
test_dual_z_endstops(Z_MIN, Z2_MIN);
|
test_dual_z_endstops(Z_MIN, Z2_MIN);
|
||||||
|
#else
|
||||||
#else // !Z_DUAL_ENDSTOPS
|
|
||||||
|
|
||||||
#if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
|
#if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
|
||||||
if (z_probe_enabled) UPDATE_ENDSTOP(Z, MIN);
|
if (z_probe_enabled) UPDATE_ENDSTOP(Z, MIN);
|
||||||
#else
|
#else
|
||||||
UPDATE_ENDSTOP(Z, MIN);
|
UPDATE_ENDSTOP(Z, MIN);
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // !Z_DUAL_ENDSTOPS
|
#endif
|
||||||
|
|
||||||
#endif // HAS_Z_MIN
|
|
||||||
|
|
||||||
// When closing the gap check the enabled probe
|
// When closing the gap check the enabled probe
|
||||||
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
|
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
|
||||||
@@ -422,27 +511,21 @@ void Endstops::update() {
|
|||||||
}
|
}
|
||||||
else { // Z +direction. Gantry up, bed down.
|
else { // Z +direction. Gantry up, bed down.
|
||||||
#if HAS_Z_MAX
|
#if HAS_Z_MAX
|
||||||
|
|
||||||
// Check both Z dual endstops
|
// Check both Z dual endstops
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
|
|
||||||
UPDATE_ENDSTOP_BIT(Z, MAX);
|
UPDATE_ENDSTOP_BIT(Z, MAX);
|
||||||
#if HAS_Z2_MAX
|
#if HAS_Z2_MAX
|
||||||
UPDATE_ENDSTOP_BIT(Z2, MAX);
|
UPDATE_ENDSTOP_BIT(Z2, MAX);
|
||||||
#else
|
#else
|
||||||
COPY_BIT(current_endstop_bits, Z_MAX, Z2_MAX);
|
COPY_BIT(current_endstop_bits, Z_MAX, Z2_MAX);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
test_dual_z_endstops(Z_MAX, Z2_MAX);
|
test_dual_z_endstops(Z_MAX, Z2_MAX);
|
||||||
|
|
||||||
// If this pin is not hijacked for the bed probe
|
// If this pin is not hijacked for the bed probe
|
||||||
// then it belongs to the Z endstop
|
// then it belongs to the Z endstop
|
||||||
#elif DISABLED(Z_MIN_PROBE_ENDSTOP) || Z_MAX_PIN != Z_MIN_PROBE_PIN
|
#elif DISABLED(Z_MIN_PROBE_ENDSTOP) || Z_MAX_PIN != Z_MIN_PROBE_PIN
|
||||||
|
|
||||||
UPDATE_ENDSTOP(Z, MAX);
|
UPDATE_ENDSTOP(Z, MAX);
|
||||||
|
#endif
|
||||||
#endif // !Z_MIN_PROBE_PIN...
|
#endif
|
||||||
#endif // Z_MAX_PIN
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -28,6 +28,7 @@
|
|||||||
#define ENDSTOPS_H
|
#define ENDSTOPS_H
|
||||||
|
|
||||||
#include "enum.h"
|
#include "enum.h"
|
||||||
|
#include "MarlinConfig.h"
|
||||||
|
|
||||||
class Endstops {
|
class Endstops {
|
||||||
|
|
||||||
@@ -36,14 +37,22 @@ class Endstops {
|
|||||||
static bool enabled, enabled_globally;
|
static bool enabled, enabled_globally;
|
||||||
static volatile char endstop_hit_bits; // use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT value
|
static volatile char endstop_hit_bits; // use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT value
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
static uint16_t
|
static uint16_t
|
||||||
#else
|
#else
|
||||||
static byte
|
static byte
|
||||||
#endif
|
#endif
|
||||||
current_endstop_bits, old_endstop_bits;
|
current_endstop_bits, old_endstop_bits;
|
||||||
|
|
||||||
Endstops() {};
|
Endstops() {
|
||||||
|
enable_globally(
|
||||||
|
#if ENABLED(ENDSTOPS_ALWAYS_ON_DEFAULT)
|
||||||
|
true
|
||||||
|
#else
|
||||||
|
false
|
||||||
|
#endif
|
||||||
|
);
|
||||||
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Initialize the endstop pins
|
* Initialize the endstop pins
|
||||||
@@ -85,6 +94,12 @@ class Endstops {
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
static void test_dual_x_endstops(const EndstopEnum es1, const EndstopEnum es2);
|
||||||
|
#endif
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
static void test_dual_y_endstops(const EndstopEnum es1, const EndstopEnum es2);
|
||||||
|
#endif
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
static void test_dual_z_endstops(const EndstopEnum es1, const EndstopEnum es2);
|
static void test_dual_z_endstops(const EndstopEnum es1, const EndstopEnum es2);
|
||||||
#endif
|
#endif
|
||||||
|
|||||||
@@ -93,6 +93,10 @@ enum EndstopEnum {
|
|||||||
X_MAX,
|
X_MAX,
|
||||||
Y_MAX,
|
Y_MAX,
|
||||||
Z_MAX,
|
Z_MAX,
|
||||||
|
X2_MIN,
|
||||||
|
X2_MAX,
|
||||||
|
Y2_MIN,
|
||||||
|
Y2_MAX,
|
||||||
Z2_MIN,
|
Z2_MIN,
|
||||||
Z2_MAX
|
Z2_MAX
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// Set/get with gcode: M301 E[extruder number, 0-2]
|
// Set/get with gcode: M301 E[extruder number, 0-2]
|
||||||
#define PID_FUNCTIONAL_RANGE 16 // If the temperature difference between the target temperature and the actual temperature
|
#define PID_FUNCTIONAL_RANGE 16 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// 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
|
||||||
@@ -448,12 +451,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -593,7 +597,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -706,14 +710,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -805,10 +811,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 250
|
#define Z_MAX_POS 250
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -828,7 +854,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -854,12 +880,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -886,6 +907,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -941,7 +980,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -952,8 +993,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -1013,14 +1054,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (8*60)
|
#define HOMING_FEEDRATE_Z (8*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1052,7 +1150,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1197,11 +1295,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1329,8 +1427,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1438,11 +1536,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1550,7 +1650,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1608,17 +1714,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1634,11 +1740,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1653,22 +1759,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1681,40 +1787,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 4
|
#define Z_HOME_BUMP_MM 4
|
||||||
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
#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.
|
#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -428,12 +431,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -573,7 +577,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -686,14 +690,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -785,10 +791,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 260
|
#define Z_MAX_POS 260
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -808,7 +834,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -834,12 +860,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -866,6 +887,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -921,7 +960,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -932,8 +973,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -993,14 +1034,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (4*60)
|
#define HOMING_FEEDRATE_Z (4*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1032,7 +1130,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1177,11 +1275,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1309,8 +1407,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1418,11 +1516,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1530,7 +1630,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1588,17 +1694,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1614,11 +1720,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1633,22 +1739,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1661,40 +1767,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -448,12 +451,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -630,7 +634,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -765,14 +769,16 @@
|
|||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
//#define XY_PROBE_SPEED 6000
|
//#define XY_PROBE_SPEED 6000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 3)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 3)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -904,10 +910,30 @@
|
|||||||
#define X_MAX_POS X_BED_SIZE
|
#define X_MAX_POS X_BED_SIZE
|
||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -927,7 +953,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -953,12 +979,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -985,6 +1006,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -1064,7 +1103,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -1075,8 +1116,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -1141,16 +1182,16 @@
|
|||||||
#define Z_SAFE_HOMING
|
#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
|
|
||||||
//Anet A6 with new X-Axis
|
//Anet A6 with new X-Axis
|
||||||
//#define Z_SAFE_HOMING_X_POINT 113 // X point for Z homing when homing all axis (G28).
|
//#define Z_SAFE_HOMING_X_POINT 113 // X point for Z homing when homing all axes (G28).
|
||||||
//#define Z_SAFE_HOMING_Y_POINT 112 // Y point for Z homing when homing all axis (G28).
|
//#define Z_SAFE_HOMING_Y_POINT 112 // Y point for Z homing when homing all axes (G28).
|
||||||
|
|
||||||
//Anet A6 with new X-Axis and defined X_HOME_POS -7, Y_HOME_POS -6
|
//Anet A6 with new X-Axis and defined X_HOME_POS -7, Y_HOME_POS -6
|
||||||
//#define Z_SAFE_HOMING_X_POINT 107 // X point for Z homing when homing all axis (G28).
|
//#define Z_SAFE_HOMING_X_POINT 107 // X point for Z homing when homing all axes (G28).
|
||||||
//#define Z_SAFE_HOMING_Y_POINT 107 // Y point for Z homing when homing all axis (G28).
|
//#define Z_SAFE_HOMING_Y_POINT 107 // Y point for Z homing when homing all axes (G28).
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1158,6 +1199,63 @@
|
|||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (4*60)
|
#define HOMING_FEEDRATE_Z (4*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1189,7 +1287,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1334,11 +1432,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1466,8 +1564,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1577,11 +1675,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1689,7 +1789,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1747,17 +1853,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1773,11 +1879,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1792,22 +1898,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1820,40 +1926,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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 60 // Seconds
|
#define THERMAL_PROTECTION_PERIOD 60 // Seconds
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 10 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 10 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 60 // Seconds
|
#define WATCH_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 5 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 5 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 5 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 5 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 180 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 180 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 2
|
#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 { 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.
|
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,10 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
// The Anet A8 original extruder is designed for 1.75mm
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +340,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +352,6 @@
|
|||||||
// Set/get with gcode: M301 E[extruder number, 0-2]
|
// Set/get with gcode: M301 E[extruder number, 0-2]
|
||||||
#define PID_FUNCTIONAL_RANGE 15 // If the temperature difference between the target temperature and the actual temperature
|
#define PID_FUNCTIONAL_RANGE 15 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -422,7 +426,7 @@
|
|||||||
// or to allow moving the extruder regardless of the hotend temperature.
|
// or to allow moving the extruder regardless of the hotend temperature.
|
||||||
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
|
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
|
||||||
#define PREVENT_COLD_EXTRUSION
|
#define PREVENT_COLD_EXTRUSION
|
||||||
#define EXTRUDE_MINTEMP 170
|
#define EXTRUDE_MINTEMP 160 // 160 guards against false tripping when the extruder fan kicks on.
|
||||||
|
|
||||||
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
|
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
|
||||||
// Note that for Bowden Extruders a too-small value here may prevent loading.
|
// Note that for Bowden Extruders a too-small value here may prevent loading.
|
||||||
@@ -434,12 +438,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -531,7 +536,7 @@
|
|||||||
* Override with M92
|
* Override with M92
|
||||||
* X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]]
|
* X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]]
|
||||||
*/
|
*/
|
||||||
#define DEFAULT_AXIS_STEPS_PER_UNIT { 100, 100, 400, 95 }
|
#define DEFAULT_AXIS_STEPS_PER_UNIT { 100, 100, 400, 100 }
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Default Max Feed Rate (mm/s)
|
* Default Max Feed Rate (mm/s)
|
||||||
@@ -579,7 +584,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -692,14 +697,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 6000
|
#define XY_PROBE_SPEED 6000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -791,10 +798,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 240
|
#define Z_MAX_POS 240
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -814,7 +841,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -840,12 +867,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -872,6 +894,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -927,7 +967,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -938,8 +980,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -999,14 +1041,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (100*60)
|
#define HOMING_FEEDRATE_XY (100*60)
|
||||||
#define HOMING_FEEDRATE_Z (4*60)
|
#define HOMING_FEEDRATE_Z (4*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1038,7 +1137,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1183,11 +1282,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1315,8 +1414,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1426,11 +1525,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1538,7 +1639,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1596,17 +1703,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1622,11 +1729,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1641,22 +1748,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1669,40 +1776,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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 60 // Seconds
|
#define THERMAL_PROTECTION_PERIOD 60 // Seconds
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 10 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 10 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 5 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 5 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 180 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 180 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 2
|
#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 { 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.
|
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
//#define SD_DETECT_INVERTED
|
//#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -139,6 +139,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -339,8 +342,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -350,7 +354,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#define K1 0.95 //smoothing factor within the PID
|
|
||||||
|
|
||||||
// Hephestos i3
|
// Hephestos i3
|
||||||
#define DEFAULT_Kp 23.05
|
#define DEFAULT_Kp 23.05
|
||||||
@@ -419,12 +422,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -564,7 +568,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -677,14 +681,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -776,10 +782,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 180
|
#define Z_MAX_POS 180
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -799,7 +825,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -825,12 +851,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -857,6 +878,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -912,7 +951,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -923,8 +964,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -984,14 +1025,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY 2000
|
#define HOMING_FEEDRATE_XY 2000
|
||||||
#define HOMING_FEEDRATE_Z 150
|
#define HOMING_FEEDRATE_Z 150
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1023,7 +1121,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1168,13 +1266,13 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
//#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* LCD Character Set
|
* LCD Character Set
|
||||||
@@ -1300,8 +1398,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1409,11 +1507,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1521,7 +1621,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1579,17 +1685,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1605,11 +1711,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1624,22 +1730,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1652,40 +1758,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 2
|
#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 { 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.
|
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -22,7 +22,7 @@
|
|||||||
|
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//================================= README ==================================
|
//================================= README ==================================
|
||||||
@@ -135,6 +135,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -341,8 +344,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -352,7 +356,6 @@
|
|||||||
// Set/get with gcode: M301 E[extruder number, 0-2]
|
// Set/get with gcode: M301 E[extruder number, 0-2]
|
||||||
#define PID_FUNCTIONAL_RANGE 50 // If the temperature difference between the target temperature and the actual temperature
|
#define PID_FUNCTIONAL_RANGE 50 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#define K1 0.95 //smoothing factor within the PID
|
|
||||||
|
|
||||||
// Tuned PID values using M303
|
// Tuned PID values using M303
|
||||||
#define DEFAULT_Kp 19.18
|
#define DEFAULT_Kp 19.18
|
||||||
@@ -429,12 +432,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -574,7 +578,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -687,14 +691,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -786,10 +792,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 210
|
#define Z_MAX_POS 210
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -809,7 +835,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -835,12 +861,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -867,6 +888,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -922,7 +961,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -933,8 +974,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -994,14 +1035,71 @@
|
|||||||
#define Z_SAFE_HOMING
|
#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (60*60)
|
#define HOMING_FEEDRATE_XY (60*60)
|
||||||
#define HOMING_FEEDRATE_Z 120
|
#define HOMING_FEEDRATE_Z 120
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1033,7 +1131,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1178,11 +1276,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1310,8 +1408,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1419,11 +1517,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1531,7 +1631,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1589,17 +1695,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1615,11 +1721,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1634,22 +1740,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1662,40 +1768,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 2.00 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.60 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 2
|
#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 { 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.
|
#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
#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])
|
#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])
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#define SD_FINISHED_RELEASECOMMAND "M104 S0\nM84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
|
#define SD_FINISHED_RELEASECOMMAND "M104 S0\nM84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
#define BLOCK_BUFFER_SIZE 32 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
|
#define BLOCK_BUFFER_SIZE 32 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
|
||||||
#else
|
#else
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 0.25 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -139,6 +139,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -339,8 +342,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -350,7 +354,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#define K1 0.95 //smoothing factor within the PID
|
|
||||||
|
|
||||||
// Witbox
|
// Witbox
|
||||||
#define DEFAULT_Kp 22.2
|
#define DEFAULT_Kp 22.2
|
||||||
@@ -419,12 +422,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -564,7 +568,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -677,14 +681,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -776,10 +782,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 200
|
#define Z_MAX_POS 200
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -799,7 +825,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -825,12 +851,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -857,6 +878,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -912,7 +951,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -923,8 +964,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -984,14 +1025,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (120*60)
|
#define HOMING_FEEDRATE_XY (120*60)
|
||||||
#define HOMING_FEEDRATE_Z 432
|
#define HOMING_FEEDRATE_Z 432
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1023,7 +1121,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1168,13 +1266,13 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
//#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* LCD Character Set
|
* LCD Character Set
|
||||||
@@ -1300,8 +1398,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1409,11 +1507,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1521,7 +1621,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1579,17 +1685,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1605,11 +1711,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1624,22 +1730,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1652,40 +1758,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 2
|
#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 { 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.
|
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -137,6 +137,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 3
|
#define EXTRUDERS 3
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -337,8 +340,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -348,7 +352,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -427,12 +430,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -572,7 +576,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -685,14 +689,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -784,10 +790,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 400
|
#define Z_MAX_POS 400
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -807,7 +833,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -833,12 +859,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -865,6 +886,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -920,7 +959,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -931,8 +972,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -992,14 +1033,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (10*60)
|
#define HOMING_FEEDRATE_Z (10*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1031,7 +1129,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1176,11 +1274,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1417,11 +1515,13 @@
|
|||||||
#define CARTESIO_UI
|
#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1529,7 +1629,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1587,17 +1693,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1613,11 +1719,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1632,22 +1738,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1660,40 +1766,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 2
|
#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 { 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.
|
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -438,12 +441,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -583,7 +587,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -696,14 +700,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -795,10 +801,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 400
|
#define Z_MAX_POS 400
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -818,7 +844,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -844,12 +870,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -876,6 +897,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -931,7 +970,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -942,8 +983,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
//#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -1003,14 +1044,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (4*60)
|
#define HOMING_FEEDRATE_Z (4*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1042,7 +1140,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1187,11 +1285,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1319,8 +1417,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1428,11 +1526,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1540,7 +1640,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1598,17 +1704,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1624,11 +1730,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1643,22 +1749,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1671,42 +1777,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
#define DEFAULT_STDDEV_FILAMENT_DIA 0.05 // Typical estimate for cheap filament
|
|
||||||
//#define DEFAULT_STDDEV_FILAMENT_DIA 0.02 // Typical advertised for higher quality filament
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT (DEFAULT_NOMINAL_FILAMENT_DIA+4*DEFAULT_STDDEV_FILAMENT_DIA) // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT (DEFAULT_NOMINAL_FILAMENT_DIA-4*DEFAULT_STDDEV_FILAMENT_DIA) // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 2
|
#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 { 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.
|
#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES true // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES true // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -609,7 +665,6 @@
|
|||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,50 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#define DEFAULT_STDDEV_FILAMENT_DIA 0.05 // Typical estimate for cheap filament
|
||||||
|
//#define DEFAULT_STDDEV_FILAMENT_DIA 0.02 // Typical advertised for higher quality filament
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN (DEFAULT_STDDEV_FILAMENT_DIA*4) // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1378,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1560,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#define K1 0.95 //smoothing factor within the PID
|
|
||||||
|
|
||||||
// Felix 2.0+ electronics with v4 Hotend
|
// Felix 2.0+ electronics with v4 Hotend
|
||||||
#define DEFAULT_Kp 12
|
#define DEFAULT_Kp 12
|
||||||
@@ -409,12 +412,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -555,7 +559,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -668,14 +672,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -767,10 +773,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 235
|
#define Z_MAX_POS 235
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -790,7 +816,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -816,12 +842,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -848,6 +869,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -903,7 +942,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -914,8 +955,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -975,14 +1016,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (4*60)
|
#define HOMING_FEEDRATE_Z (4*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1014,7 +1112,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1159,13 +1257,13 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
//#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* LCD Character Set
|
* LCD Character Set
|
||||||
@@ -1291,8 +1389,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1400,11 +1498,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1512,7 +1612,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1570,17 +1676,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1596,11 +1702,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1615,22 +1721,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1643,40 +1749,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 3
|
||||||
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
#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.
|
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 2
|
#define EXTRUDERS 2
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#define K1 0.95 //smoothing factor within the PID
|
|
||||||
|
|
||||||
// Felix 2.0+ electronics with v4 Hotend
|
// Felix 2.0+ electronics with v4 Hotend
|
||||||
#define DEFAULT_Kp 12
|
#define DEFAULT_Kp 12
|
||||||
@@ -409,12 +412,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -555,7 +559,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -668,14 +672,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -767,10 +773,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 235
|
#define Z_MAX_POS 235
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -790,7 +816,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -816,12 +842,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -848,6 +869,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -903,7 +942,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -914,8 +955,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -975,14 +1016,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (4*60)
|
#define HOMING_FEEDRATE_Z (4*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1014,7 +1112,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1159,13 +1257,13 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
//#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* LCD Character Set
|
* LCD Character Set
|
||||||
@@ -1291,8 +1389,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1400,11 +1498,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1512,7 +1612,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1570,17 +1676,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1596,11 +1702,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1615,22 +1721,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1643,40 +1749,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -433,12 +436,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -578,7 +582,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -690,14 +694,16 @@
|
|||||||
|
|
||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 7500
|
#define XY_PROBE_SPEED 7500
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -788,10 +794,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 175
|
#define Z_MAX_POS 175
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
//#define MIN_SOFTWARE_ENDSTOPS
|
//#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -811,7 +837,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -837,12 +863,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -869,6 +890,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -926,7 +965,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y 10
|
#define GRID_MAX_POINTS_Y 10
|
||||||
|
|
||||||
@@ -937,8 +978,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 25
|
#define UBL_PROBE_PT_3_Y 25
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -998,14 +1039,71 @@
|
|||||||
#define Z_SAFE_HOMING
|
#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (40*60)
|
#define HOMING_FEEDRATE_XY (40*60)
|
||||||
#define HOMING_FEEDRATE_Z (55)
|
#define HOMING_FEEDRATE_Z (55)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1037,7 +1135,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1182,11 +1280,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1314,8 +1412,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1423,11 +1521,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1535,7 +1635,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1593,17 +1699,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1619,11 +1725,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1638,22 +1744,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
#define NUM_SERVOS 2 // Servo index starts with 0 for M280 command
|
#define NUM_SERVOS 2 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1666,40 +1772,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
#define DEACTIVATE_SERVOS_AFTER_MOVE
|
#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 40 // Seconds
|
#define WATCH_TEMP_PERIOD 40 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 2
|
#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 { 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.
|
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -609,7 +665,6 @@
|
|||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#define K1 0.95 //smoothing factor within the PID
|
|
||||||
|
|
||||||
// Geeetech MK8 Extruder
|
// Geeetech MK8 Extruder
|
||||||
#define DEFAULT_Kp 12.33
|
#define DEFAULT_Kp 12.33
|
||||||
@@ -443,12 +446,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -588,7 +592,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -701,14 +705,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -800,10 +806,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 200
|
#define Z_MAX_POS 200
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -823,7 +849,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -849,12 +875,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -881,6 +902,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -936,7 +975,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -947,8 +988,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -1008,14 +1049,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (4*60)
|
#define HOMING_FEEDRATE_Z (4*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1047,7 +1145,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1192,11 +1290,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1324,8 +1422,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1433,11 +1531,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1545,7 +1645,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1603,17 +1709,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1629,11 +1735,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1648,22 +1754,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1676,46 +1782,10 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Customize common displays for GT2560
|
* Customize common displays for GT2560
|
||||||
*/
|
*/
|
||||||
#if ENABLED(ULTIMAKERCONTROLLER) || ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) || ENABLED(G3D_PANEL)
|
#if ENABLED(ULTIMAKERCONTROLLER) || ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) || ENABLED(G3D_PANEL) || ENABLED(MKS_MINI_12864)
|
||||||
#define SDSUPPORT // Force SD Card support on for these displays
|
#define SDSUPPORT // Force SD Card support on for these displays
|
||||||
#elif ENABLED(ULTRA_LCD) && ENABLED(DOGLCD) // No panel, just graphical LCD?
|
#elif ENABLED(ULTRA_LCD) && ENABLED(DOGLCD) // No panel, just graphical LCD?
|
||||||
#define LCD_WIDTH 20 // Default is 22. For this Geeetech use 20
|
#define LCD_WIDTH 20 // Default is 22. For this Geeetech use 20
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -428,12 +431,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -573,7 +577,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -686,14 +690,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -785,10 +791,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 170
|
#define Z_MAX_POS 170
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -808,7 +834,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -834,12 +860,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -866,6 +887,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -921,7 +960,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -932,8 +973,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -993,14 +1034,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (4*60)
|
#define HOMING_FEEDRATE_Z (4*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1032,7 +1130,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1177,11 +1275,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1418,11 +1516,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1530,7 +1630,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1588,17 +1694,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1614,11 +1720,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1633,22 +1739,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
#define NUM_SERVOS 1 // Servo index starts with 0 for M280 command
|
#define NUM_SERVOS 1 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1661,40 +1767,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -432,12 +435,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -577,7 +581,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -690,14 +694,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -789,10 +795,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 185
|
#define Z_MAX_POS 185
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -812,7 +838,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -838,12 +864,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -870,6 +891,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -925,7 +964,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -936,8 +977,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -997,14 +1038,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (4*60)
|
#define HOMING_FEEDRATE_Z (4*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1036,7 +1134,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1181,11 +1279,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1313,8 +1411,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1422,11 +1520,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1534,7 +1634,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1592,17 +1698,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1618,11 +1724,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1637,22 +1743,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1665,40 +1771,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 1
|
#define Z_HOME_BUMP_MM 1
|
||||||
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
#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.
|
#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
//#define EXTENDED_CAPABILITIES_REPORT
|
//#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -42,7 +42,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -141,6 +141,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -344,8 +347,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -355,7 +359,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -436,12 +439,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -593,7 +597,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -710,14 +714,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
//#define XY_PROBE_SPEED 8000
|
//#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
//#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
//#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
//#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
//#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -809,10 +815,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 180
|
#define Z_MAX_POS 180
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -832,7 +858,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -858,12 +884,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -894,6 +915,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -949,7 +988,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -960,8 +1001,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -1021,14 +1062,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (4*60)
|
#define HOMING_FEEDRATE_Z (4*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1060,7 +1158,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1205,11 +1303,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1337,8 +1435,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1446,11 +1544,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1558,7 +1658,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1616,17 +1722,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1642,11 +1748,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1661,22 +1767,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1689,40 +1795,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 2
|
#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 { 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.
|
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
15
Marlin/example_configurations/Micromake/C1/README.md
Normal file
15
Marlin/example_configurations/Micromake/C1/README.md
Normal file
@@ -0,0 +1,15 @@
|
|||||||
|
# Micromake C1
|
||||||
|
|
||||||
|
### In the folder "basic"
|
||||||
|
Configuration files for Micromake C1 without mods
|
||||||
|
- English LCD 2X16 Characters
|
||||||
|
- Motors 16 STEPS
|
||||||
|
- No heated bed
|
||||||
|
- No probe, etc.
|
||||||
|
- Like a standard C1 as shipped by Micromake.
|
||||||
|
|
||||||
|
### In the folder "enhanced"
|
||||||
|
Configuration files for Micromake C1 with…
|
||||||
|
- 128 STEPS configured with jumper on the motherboard (all open for 128 Steps).
|
||||||
|
- Capacitive Probe (Adjust offsets at your convenience)
|
||||||
|
- French language with no accents for Japanese LCD.
|
||||||
1774
Marlin/example_configurations/Micromake/C1/basic/Configuration.h
Normal file
1774
Marlin/example_configurations/Micromake/C1/basic/Configuration.h
Normal file
File diff suppressed because it is too large
Load Diff
1774
Marlin/example_configurations/Micromake/C1/enhanced/Configuration.h
Normal file
1774
Marlin/example_configurations/Micromake/C1/enhanced/Configuration.h
Normal file
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -428,12 +431,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -573,7 +577,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -686,14 +690,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -785,10 +791,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 200
|
#define Z_MAX_POS 200
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -808,7 +834,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -834,12 +860,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -866,6 +887,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -921,7 +960,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -932,8 +973,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -993,14 +1034,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (4*60)
|
#define HOMING_FEEDRATE_Z (4*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1032,7 +1130,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1177,11 +1275,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1309,8 +1407,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1418,11 +1516,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1530,7 +1630,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1588,17 +1694,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1614,11 +1720,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1633,22 +1739,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1661,40 +1767,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -139,6 +139,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1 // Single extruder. Set to 2 for dual extruders
|
#define EXTRUDERS 1 // Single extruder. Set to 2 for dual extruders
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -339,8 +342,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -350,7 +354,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -424,12 +427,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -571,7 +575,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -684,14 +688,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -783,10 +789,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 254 // RigidBot regular and Big are 254mm
|
#define Z_MAX_POS 254 // RigidBot regular and Big are 254mm
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -806,7 +832,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -832,12 +858,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -864,6 +885,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -919,7 +958,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -930,8 +971,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -991,14 +1032,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (15*60)
|
#define HOMING_FEEDRATE_Z (15*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1030,7 +1128,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1175,11 +1273,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1307,8 +1405,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1418,11 +1516,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1530,7 +1630,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1588,17 +1694,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1614,11 +1720,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1633,22 +1739,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1661,40 +1767,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 2
|
#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 { 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.
|
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -166,6 +166,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -366,8 +369,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -377,7 +381,6 @@
|
|||||||
// Set/get with gcode: M301 E[extruder number, 0-2]
|
// Set/get with gcode: M301 E[extruder number, 0-2]
|
||||||
#define PID_FUNCTIONAL_RANGE 20 // If the temperature difference between the target temperature and the actual temperature
|
#define PID_FUNCTIONAL_RANGE 20 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#define K1 0.95 //smoothing factor within the PID
|
|
||||||
|
|
||||||
// Merlin Hotend: From Autotune
|
// Merlin Hotend: From Autotune
|
||||||
#define DEFAULT_Kp 24.5
|
#define DEFAULT_Kp 24.5
|
||||||
@@ -440,12 +443,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -585,7 +589,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -698,14 +702,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -797,10 +803,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 225
|
#define Z_MAX_POS 225
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -820,7 +846,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -846,12 +872,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -878,6 +899,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -933,7 +972,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -944,8 +985,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -1005,14 +1046,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (40*60)
|
#define HOMING_FEEDRATE_XY (40*60)
|
||||||
#define HOMING_FEEDRATE_Z (10*60)
|
#define HOMING_FEEDRATE_Z (10*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1044,7 +1142,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1189,13 +1287,13 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
//#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* LCD Character Set
|
* LCD Character Set
|
||||||
@@ -1321,8 +1419,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1430,11 +1528,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1542,7 +1642,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1600,17 +1706,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1626,11 +1732,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1645,22 +1751,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1673,40 +1779,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#define X_HOME_BUMP_MM 3
|
#define X_HOME_BUMP_MM 3
|
||||||
#define Y_HOME_BUMP_MM 3
|
#define Y_HOME_BUMP_MM 3
|
||||||
#define Z_HOME_BUMP_MM 3
|
#define Z_HOME_BUMP_MM 3
|
||||||
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
#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.
|
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -428,12 +431,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -604,7 +608,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -717,14 +721,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -816,10 +822,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 170
|
#define Z_MAX_POS 170
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -839,7 +865,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -865,12 +891,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -897,6 +918,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -952,7 +991,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -963,8 +1004,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
//#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -1024,14 +1065,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (6*60)
|
#define HOMING_FEEDRATE_Z (6*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1063,7 +1161,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1212,7 +1310,7 @@
|
|||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
|
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk,
|
||||||
* zh_CN, zh_TW, test
|
* zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1340,8 +1438,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1449,11 +1547,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1561,7 +1661,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1619,17 +1725,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
#define RGB_LED
|
#define RGB_LED
|
||||||
@@ -1645,11 +1751,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1664,22 +1770,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1692,40 +1798,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -246,48 +248,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -334,12 +337,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 2
|
#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 { 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.
|
#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -423,8 +426,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -455,6 +471,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -464,12 +497,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -506,6 +541,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -524,14 +561,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -564,6 +616,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -592,13 +648,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -645,23 +700,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -681,7 +731,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -706,7 +756,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -774,6 +824,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -884,7 +943,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -898,7 +957,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -913,46 +984,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -961,24 +1044,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -993,8 +1074,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1004,7 +1085,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1013,27 +1094,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1197,6 +1285,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1213,13 +1342,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1388,4 +1524,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Sample configuration file for TinyBoy2 L10/L16
|
* Sample configuration file for TinyBoy2 L10/L16
|
||||||
@@ -158,6 +158,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -363,8 +366,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -374,7 +378,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -478,12 +481,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -624,7 +628,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -737,14 +741,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -841,10 +847,30 @@
|
|||||||
#define Z_MAX_POS 158
|
#define Z_MAX_POS 158
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -864,7 +890,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -890,12 +916,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -922,6 +943,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -977,7 +1016,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -988,8 +1029,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -1049,14 +1090,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (40*60)
|
#define HOMING_FEEDRATE_XY (40*60)
|
||||||
#define HOMING_FEEDRATE_Z (3*60)
|
#define HOMING_FEEDRATE_Z (3*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1088,7 +1186,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1233,11 +1331,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1365,8 +1463,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1474,11 +1572,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1586,7 +1686,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1644,17 +1750,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1670,11 +1776,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1689,22 +1795,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1717,40 +1823,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 2
|
#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 { 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.
|
//#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Sample configuration file for Vellemann K8200
|
* Sample configuration file for Vellemann K8200
|
||||||
@@ -156,6 +156,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -356,8 +359,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -367,7 +371,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -458,12 +461,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -602,7 +606,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -715,14 +719,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -815,10 +821,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 200
|
#define Z_MAX_POS 200
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -838,7 +864,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -864,12 +890,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -896,6 +917,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -951,7 +990,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -962,8 +1003,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -1023,14 +1064,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (4*60)
|
#define HOMING_FEEDRATE_Z (4*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1062,7 +1160,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1210,11 +1308,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1342,8 +1440,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1451,11 +1549,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1563,7 +1663,8 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
#endif // K8200_VM8201
|
#endif // K8200_VM8201
|
||||||
|
|
||||||
@@ -1623,17 +1724,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1649,11 +1750,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1668,22 +1769,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1696,40 +1797,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -41,7 +41,7 @@
|
|||||||
|
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -57,18 +57,20 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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)
|
||||||
// K8200 has weak heaters/power supply by default, so you have to relax!
|
// K8200 has weak heaters/power supply by default, so you have to relax!
|
||||||
@@ -76,13 +78,16 @@
|
|||||||
#define THERMAL_PROTECTION_HYSTERESIS 8 // 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, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
// K8200 has weak heaters/power supply by default, so you have to relax!
|
// K8200 has weak heaters/power supply by default, so you have to relax!
|
||||||
#define WATCH_TEMP_PERIOD 30 // Seconds
|
#define WATCH_TEMP_PERIOD 30 // Seconds
|
||||||
@@ -99,13 +104,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 10 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 10 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -136,6 +135,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -270,48 +272,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -358,12 +361,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 2
|
#define Z_HOME_BUMP_MM 2
|
||||||
#define HOMING_BUMP_DIVISOR {4, 4, 8} // 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 homing includes X and Y, do a diagonal move 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
|
||||||
@@ -447,8 +450,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -479,6 +495,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -488,7 +521,7 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#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.
|
||||||
@@ -530,6 +563,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -548,14 +583,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -588,6 +638,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -616,13 +670,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -669,23 +722,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -705,7 +753,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -730,7 +778,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -820,6 +868,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -930,7 +987,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -944,7 +1001,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -959,46 +1028,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -1007,24 +1088,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1039,8 +1118,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1050,7 +1129,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1059,27 +1138,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1243,6 +1329,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1259,13 +1386,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1434,4 +1568,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -428,12 +431,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -573,7 +577,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -686,14 +690,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -785,10 +791,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 190
|
#define Z_MAX_POS 190
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -808,7 +834,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -834,12 +860,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -866,6 +887,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -921,7 +960,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -932,8 +973,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -993,14 +1034,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (8*60)
|
#define HOMING_FEEDRATE_Z (8*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1032,7 +1130,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1177,11 +1275,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1309,8 +1407,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1418,11 +1516,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1530,7 +1630,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1588,17 +1694,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1614,11 +1720,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1633,22 +1739,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1661,40 +1767,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#define X_HOME_BUMP_MM 10
|
#define X_HOME_BUMP_MM 10
|
||||||
#define Y_HOME_BUMP_MM 10
|
#define Y_HOME_BUMP_MM 10
|
||||||
#define Z_HOME_BUMP_MM 3
|
#define Z_HOME_BUMP_MM 3
|
||||||
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
#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.
|
#define QUICK_HOME // If homing includes X and Y, do a diagonal move 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
|
||||||
@@ -434,8 +437,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -466,6 +482,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -475,12 +508,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -517,6 +552,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -535,14 +572,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -575,6 +627,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -603,13 +659,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -656,23 +711,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -692,7 +742,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -717,7 +767,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -807,6 +857,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -917,7 +976,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -931,7 +990,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -946,46 +1017,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -994,24 +1077,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1026,8 +1107,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1037,7 +1118,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1046,27 +1127,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1230,6 +1318,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1246,13 +1375,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1421,4 +1557,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 2
|
#define EXTRUDERS 2
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -428,12 +431,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -573,7 +577,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -686,14 +690,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -785,10 +791,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 190
|
#define Z_MAX_POS 190
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -808,7 +834,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -834,12 +860,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -866,6 +887,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -921,7 +960,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -932,8 +973,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -993,14 +1034,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (8*60)
|
#define HOMING_FEEDRATE_Z (8*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1032,7 +1130,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1177,11 +1275,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1309,8 +1407,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1418,11 +1516,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1530,7 +1630,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1588,17 +1694,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1614,11 +1720,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1633,22 +1739,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1661,40 +1767,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
1726
Marlin/example_configurations/Wanhao/Duplicator 6/Configuration.h
Normal file
1726
Marlin/example_configurations/Wanhao/Duplicator 6/Configuration.h
Normal file
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -428,12 +431,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -573,7 +577,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -686,14 +690,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 8000
|
#define XY_PROBE_SPEED 8000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z probes require clearance when deploying, stowing, and moving between
|
* Z probes require clearance when deploying, stowing, and moving between
|
||||||
@@ -785,10 +791,30 @@
|
|||||||
#define Y_MAX_POS Y_BED_SIZE
|
#define Y_MAX_POS Y_BED_SIZE
|
||||||
#define Z_MAX_POS 200
|
#define Z_MAX_POS 200
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -808,7 +834,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -834,12 +860,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -866,6 +887,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
#define ENABLE_LEVELING_FADE_HEIGHT
|
#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -921,7 +960,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -932,8 +973,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X 180
|
#define UBL_PROBE_PT_3_X 180
|
||||||
#define UBL_PROBE_PT_3_Y 20
|
#define UBL_PROBE_PT_3_Y 20
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -993,14 +1034,71 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Homing speeds (mm/m)
|
// Homing speeds (mm/m)
|
||||||
#define HOMING_FEEDRATE_XY (50*60)
|
#define HOMING_FEEDRATE_XY (50*60)
|
||||||
#define HOMING_FEEDRATE_Z (4*60)
|
#define HOMING_FEEDRATE_Z (4*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1032,7 +1130,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1177,11 +1275,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1309,8 +1407,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1418,11 +1516,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1530,7 +1630,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1588,17 +1694,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1614,11 +1720,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1633,22 +1739,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1661,40 +1767,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -438,12 +441,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -486,7 +490,7 @@
|
|||||||
// 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
|
||||||
#define DELTA_CALIBRATION_MENU
|
//#define DELTA_CALIBRATION_MENU
|
||||||
|
|
||||||
// uncomment to add G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results)
|
// uncomment to add G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results)
|
||||||
#define DELTA_AUTO_CALIBRATION
|
#define DELTA_AUTO_CALIBRATION
|
||||||
@@ -496,10 +500,16 @@
|
|||||||
#if ENABLED(DELTA_AUTO_CALIBRATION)
|
#if ENABLED(DELTA_AUTO_CALIBRATION)
|
||||||
// set the default number of probe points : n*n (1 -> 7)
|
// set the default number of probe points : n*n (1 -> 7)
|
||||||
#define DELTA_CALIBRATION_DEFAULT_POINTS 4
|
#define DELTA_CALIBRATION_DEFAULT_POINTS 4
|
||||||
|
|
||||||
|
// Enable and set these values based on results of 'G33 A'
|
||||||
|
//#define H_FACTOR 1.01
|
||||||
|
//#define R_FACTOR 2.61
|
||||||
|
//#define A_FACTOR 0.87
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU)
|
#if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU)
|
||||||
// Set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 for non-eccentric probes
|
// Set the radius for the calibration probe points - max 0.9 * DELTA_PRINTABLE_RADIUS for non-eccentric probes
|
||||||
#define DELTA_CALIBRATION_RADIUS 73.5 // mm
|
#define DELTA_CALIBRATION_RADIUS 73.5 // mm
|
||||||
// Set the steprate for papertest probing
|
// Set the steprate for papertest probing
|
||||||
#define PROBE_MANUALLY_STEP 0.025
|
#define PROBE_MANUALLY_STEP 0.025
|
||||||
@@ -647,7 +657,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -760,14 +770,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 5000
|
#define XY_PROBE_SPEED 5000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST) / 6
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST) / 6
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* 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
|
||||||
@@ -909,10 +921,30 @@
|
|||||||
#define Y_MAX_POS DELTA_PRINTABLE_RADIUS
|
#define Y_MAX_POS DELTA_PRINTABLE_RADIUS
|
||||||
#define Z_MAX_POS MANUAL_Z_HOME_POS
|
#define Z_MAX_POS MANUAL_Z_HOME_POS
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
//#define MIN_SOFTWARE_ENDSTOPS
|
//#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -932,7 +964,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -958,12 +990,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -990,6 +1017,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
//#define ENABLE_LEVELING_FADE_HEIGHT
|
//#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -1047,7 +1092,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -1060,8 +1107,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X _PX(DELTA_PROBEABLE_RADIUS, 240)
|
#define UBL_PROBE_PT_3_X _PX(DELTA_PROBEABLE_RADIUS, 240)
|
||||||
#define UBL_PROBE_PT_3_Y _PY(DELTA_PROBEABLE_RADIUS, 240)
|
#define UBL_PROBE_PT_3_Y _PY(DELTA_PROBEABLE_RADIUS, 240)
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -1121,13 +1168,70 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Delta only homes to Z
|
// Delta only homes to Z
|
||||||
#define HOMING_FEEDRATE_Z (100*60)
|
#define HOMING_FEEDRATE_Z (100*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1159,7 +1263,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1304,11 +1408,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1437,8 +1541,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1546,11 +1650,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1658,7 +1764,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1716,17 +1828,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1742,11 +1854,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1761,22 +1873,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1789,40 +1901,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 1.95 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.20 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 5 // deltas need the same for all three axes
|
#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes
|
||||||
#define HOMING_BUMP_DIVISOR {10, 10, 10} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
#define HOMING_BUMP_DIVISOR { 10, 10, 10 } // 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 homing includes X and Y, do a diagonal move 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
|
||||||
@@ -436,8 +439,21 @@
|
|||||||
#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -468,6 +484,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -477,12 +510,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -519,6 +554,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -537,14 +574,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -577,6 +629,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -611,7 +667,6 @@
|
|||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -658,23 +713,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -694,7 +744,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -719,7 +769,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -809,6 +859,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -919,7 +978,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -933,7 +992,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -948,46 +1019,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -996,24 +1079,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1028,8 +1109,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1039,7 +1120,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1048,27 +1129,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1232,6 +1320,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1248,13 +1377,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1423,4 +1559,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -438,12 +441,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -496,10 +500,16 @@
|
|||||||
#if ENABLED(DELTA_AUTO_CALIBRATION)
|
#if ENABLED(DELTA_AUTO_CALIBRATION)
|
||||||
// set the default number of probe points : n*n (1 -> 7)
|
// set the default number of probe points : n*n (1 -> 7)
|
||||||
#define DELTA_CALIBRATION_DEFAULT_POINTS 4
|
#define DELTA_CALIBRATION_DEFAULT_POINTS 4
|
||||||
|
|
||||||
|
// Enable and set these values based on results of 'G33 A'
|
||||||
|
//#define H_FACTOR 1.01
|
||||||
|
//#define R_FACTOR 2.61
|
||||||
|
//#define A_FACTOR 0.87
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU)
|
#if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU)
|
||||||
// Set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 for non-eccentric probes
|
// Set the radius for the calibration probe points - max 0.9 * DELTA_PRINTABLE_RADIUS for non-eccentric probes
|
||||||
#define DELTA_CALIBRATION_RADIUS 73.5 // mm
|
#define DELTA_CALIBRATION_RADIUS 73.5 // mm
|
||||||
// Set the steprate for papertest probing
|
// Set the steprate for papertest probing
|
||||||
#define PROBE_MANUALLY_STEP 0.025
|
#define PROBE_MANUALLY_STEP 0.025
|
||||||
@@ -647,7 +657,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -760,14 +770,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 2000
|
#define XY_PROBE_SPEED 2000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* 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
|
||||||
@@ -909,10 +921,30 @@
|
|||||||
#define Y_MAX_POS DELTA_PRINTABLE_RADIUS
|
#define Y_MAX_POS DELTA_PRINTABLE_RADIUS
|
||||||
#define Z_MAX_POS MANUAL_Z_HOME_POS
|
#define Z_MAX_POS MANUAL_Z_HOME_POS
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -932,7 +964,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -958,12 +990,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -990,6 +1017,24 @@
|
|||||||
// at which point movement will be level to the machine's XY plane.
|
// at which point movement will be level to the machine's XY plane.
|
||||||
// The height can be set with M420 Z<height>
|
// The height can be set with M420 Z<height>
|
||||||
//#define ENABLE_LEVELING_FADE_HEIGHT
|
//#define ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -1041,7 +1086,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -1054,8 +1101,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X _PX(DELTA_PROBEABLE_RADIUS, 240)
|
#define UBL_PROBE_PT_3_X _PX(DELTA_PROBEABLE_RADIUS, 240)
|
||||||
#define UBL_PROBE_PT_3_Y _PY(DELTA_PROBEABLE_RADIUS, 240)
|
#define UBL_PROBE_PT_3_Y _PY(DELTA_PROBEABLE_RADIUS, 240)
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -1115,13 +1162,70 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Delta only homes to Z
|
// Delta only homes to Z
|
||||||
#define HOMING_FEEDRATE_Z (45*60)
|
#define HOMING_FEEDRATE_Z (45*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1153,7 +1257,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1298,11 +1402,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1430,8 +1534,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1539,11 +1643,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1651,7 +1757,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1709,17 +1821,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1735,11 +1847,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1754,22 +1866,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1782,40 +1894,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 5 // deltas need the same for all three axes
|
#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes
|
||||||
#define HOMING_BUMP_DIVISOR {10, 10, 10} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
#define HOMING_BUMP_DIVISOR { 10, 10, 10 } // 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 homing includes X and Y, do a diagonal move 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
|
||||||
@@ -436,8 +439,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -468,6 +484,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -477,12 +510,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -519,6 +554,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -537,14 +574,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -577,6 +629,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -605,13 +661,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -658,23 +713,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -694,7 +744,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -719,7 +769,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -809,6 +859,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -919,7 +978,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -933,7 +992,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -948,46 +1019,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -996,24 +1079,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1028,8 +1109,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1039,7 +1120,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1048,27 +1129,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1232,6 +1320,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1248,13 +1377,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1423,4 +1559,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
@@ -37,7 +37,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
#define CONFIGURATION_H_VERSION 010100
|
#define CONFIGURATION_H_VERSION 010107
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Getting Started =============================
|
//============================= Getting Started =============================
|
||||||
@@ -136,6 +136,9 @@
|
|||||||
// :[1, 2, 3, 4, 5]
|
// :[1, 2, 3, 4, 5]
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
// Generally expected filament diameter (1.75, 2.85, 3.0, ...). Used for Volumetric, Filament Width Sensor, etc.
|
||||||
|
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0
|
||||||
|
|
||||||
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
// For Cyclops or any "multi-extruder" that shares a single nozzle.
|
||||||
//#define SINGLENOZZLE
|
//#define SINGLENOZZLE
|
||||||
|
|
||||||
@@ -336,8 +339,9 @@
|
|||||||
|
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#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
|
||||||
|
#define PID_K1 0.95 // Smoothing factor within the PID
|
||||||
#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_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.
|
||||||
@@ -347,7 +351,6 @@
|
|||||||
// 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 10 // If the temperature difference between the target temperature and the actual temperature
|
||||||
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
|
||||||
#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
|
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
|
||||||
@@ -428,12 +431,13 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* If you get "Thermal Runaway" or "Heating failed" errors the
|
* If you get "Thermal Runaway" or "Heating failed" errors the
|
||||||
* details can be tuned in Configuration_adv.h
|
* details can be tuned in Configuration_adv.h
|
||||||
@@ -486,10 +490,16 @@
|
|||||||
#if ENABLED(DELTA_AUTO_CALIBRATION)
|
#if ENABLED(DELTA_AUTO_CALIBRATION)
|
||||||
// set the default number of probe points : n*n (1 -> 7)
|
// set the default number of probe points : n*n (1 -> 7)
|
||||||
#define DELTA_CALIBRATION_DEFAULT_POINTS 4
|
#define DELTA_CALIBRATION_DEFAULT_POINTS 4
|
||||||
|
|
||||||
|
// Enable and set these values based on results of 'G33 A'
|
||||||
|
//#define H_FACTOR 1.01
|
||||||
|
//#define R_FACTOR 2.61
|
||||||
|
//#define A_FACTOR 0.87
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU)
|
#if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU)
|
||||||
// Set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 for non-eccentric probes
|
// Set the radius for the calibration probe points - max 0.9 * DELTA_PRINTABLE_RADIUS for non-eccentric probes
|
||||||
#define DELTA_CALIBRATION_RADIUS 121.5 // mm
|
#define DELTA_CALIBRATION_RADIUS 121.5 // mm
|
||||||
// Set the steprate for papertest probing
|
// Set the steprate for papertest probing
|
||||||
#define PROBE_MANUALLY_STEP 0.025
|
#define PROBE_MANUALLY_STEP 0.025
|
||||||
@@ -637,7 +647,7 @@
|
|||||||
// @section probes
|
// @section probes
|
||||||
|
|
||||||
//
|
//
|
||||||
// See http://marlinfw.org/configuration/probes.html
|
// See http://marlinfw.org/docs/configuration/probes.html
|
||||||
//
|
//
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -645,7 +655,7 @@
|
|||||||
*
|
*
|
||||||
* Enable this option for a probe connected to the Z Min endstop pin.
|
* Enable this option for a probe connected to the Z Min endstop pin.
|
||||||
*/
|
*/
|
||||||
//#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Z_MIN_PROBE_ENDSTOP
|
* Z_MIN_PROBE_ENDSTOP
|
||||||
@@ -666,7 +676,7 @@
|
|||||||
* disastrous consequences. Use with caution and do your homework.
|
* disastrous consequences. Use with caution and do your homework.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
#define Z_MIN_PROBE_ENDSTOP
|
//#define Z_MIN_PROBE_ENDSTOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Probe Type
|
* Probe Type
|
||||||
@@ -750,14 +760,16 @@
|
|||||||
// X and Y axis travel speed (mm/m) between probes
|
// X and Y axis travel speed (mm/m) between probes
|
||||||
#define XY_PROBE_SPEED 4000
|
#define XY_PROBE_SPEED 4000
|
||||||
|
|
||||||
// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH)
|
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
|
||||||
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
|
||||||
|
|
||||||
// Speed for the "accurate" probe of each point
|
// Speed for the "accurate" probe of each point
|
||||||
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
|
||||||
|
|
||||||
// Use double touch for probing
|
// The number of probes to perform at each point.
|
||||||
//#define PROBE_DOUBLE_TOUCH
|
// Set to 2 for a fast/slow probe, using the second probe result.
|
||||||
|
// Set to 3 or more for slow probes, averaging the results.
|
||||||
|
//#define MULTIPLE_PROBING 2
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* 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
|
||||||
@@ -896,10 +908,30 @@
|
|||||||
#define Y_MAX_POS DELTA_PRINTABLE_RADIUS
|
#define Y_MAX_POS DELTA_PRINTABLE_RADIUS
|
||||||
#define Z_MAX_POS MANUAL_Z_HOME_POS
|
#define Z_MAX_POS MANUAL_Z_HOME_POS
|
||||||
|
|
||||||
// If enabled, axes won't move below MIN_POS in response to movement commands.
|
/**
|
||||||
|
* Software Endstops
|
||||||
|
*
|
||||||
|
* - Prevent moves outside the set machine bounds.
|
||||||
|
* - Individual axes can be disabled, if desired.
|
||||||
|
* - X and Y only apply to Cartesian robots.
|
||||||
|
* - Use 'M211' to set software endstops on/off or report current state
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Min software endstops curtail movement below minimum coordinate bounds
|
||||||
#define MIN_SOFTWARE_ENDSTOPS
|
#define MIN_SOFTWARE_ENDSTOPS
|
||||||
// If enabled, axes won't move above MAX_POS in response to movement commands.
|
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MIN_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Max software endstops curtail movement above maximum coordinate bounds
|
||||||
#define MAX_SOFTWARE_ENDSTOPS
|
#define MAX_SOFTWARE_ENDSTOPS
|
||||||
|
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_X
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Y
|
||||||
|
#define MAX_SOFTWARE_ENDSTOP_Z
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Filament Runout Sensor
|
* Filament Runout Sensor
|
||||||
@@ -919,7 +951,7 @@
|
|||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================== Bed Leveling ==============================
|
//=============================== Bed Leveling ==============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
// @section bedlevel
|
// @section calibrate
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
* Choose one of the options below to enable G29 Bed Leveling. The parameters
|
||||||
@@ -945,12 +977,7 @@
|
|||||||
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
* - AUTO_BED_LEVELING_UBL (Unified Bed Leveling)
|
||||||
* A comprehensive bed leveling system combining the features and benefits
|
* A comprehensive bed leveling system combining the features and benefits
|
||||||
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
* of other systems. UBL also includes integrated Mesh Generation, Mesh
|
||||||
* Validation and Mesh Editing systems. Currently, UBL is only checked out
|
* Validation and Mesh Editing systems.
|
||||||
* for Cartesian Printers. That said, it was primarily designed to correct
|
|
||||||
* poor quality Delta Printers. If you feel adventurous and have a Delta,
|
|
||||||
* please post an issue if something doesn't work correctly. Initially,
|
|
||||||
* you will need to set a reduced bed size so you have a rectangular area
|
|
||||||
* to test on.
|
|
||||||
*
|
*
|
||||||
* - MESH_BED_LEVELING
|
* - MESH_BED_LEVELING
|
||||||
* Probe a grid manually
|
* Probe a grid manually
|
||||||
@@ -981,6 +1008,24 @@
|
|||||||
// Set the boundaries for probing (where the probe can reach).
|
// Set the boundaries for probing (where the probe can reach).
|
||||||
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
|
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
|
||||||
|
|
||||||
|
|
||||||
|
// For Cartesian machines, instead of dividing moves on mesh boundaries,
|
||||||
|
// split up moves into short segments like a Delta. This follows the
|
||||||
|
// contours of the bed more closely than edge-to-edge straight moves.
|
||||||
|
#define SEGMENT_LEVELED_MOVES
|
||||||
|
#define LEVELED_SEGMENT_LENGTH 5.0 // (mm) Length of all segments (except the last one)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable the G26 Mesh Validation Pattern tool.
|
||||||
|
*/
|
||||||
|
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
|
||||||
|
#if ENABLED(G26_MESH_VALIDATION)
|
||||||
|
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
|
||||||
|
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
|
||||||
|
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
@@ -1036,7 +1081,9 @@
|
|||||||
//========================= Unified Bed Leveling ============================
|
//========================= Unified Bed Leveling ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
|
||||||
#define UBL_MESH_INSET 1 // Mesh inset margin on print area
|
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
|
||||||
|
|
||||||
|
#define MESH_INSET 1 // Mesh inset margin on print area
|
||||||
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
|
||||||
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
|
||||||
|
|
||||||
@@ -1049,8 +1096,8 @@
|
|||||||
#define UBL_PROBE_PT_3_X _PX(DELTA_PROBEABLE_RADIUS, 240)
|
#define UBL_PROBE_PT_3_X _PX(DELTA_PROBEABLE_RADIUS, 240)
|
||||||
#define UBL_PROBE_PT_3_Y _PY(DELTA_PROBEABLE_RADIUS, 240)
|
#define UBL_PROBE_PT_3_Y _PY(DELTA_PROBEABLE_RADIUS, 240)
|
||||||
|
|
||||||
#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation
|
|
||||||
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
|
||||||
|
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
|
||||||
|
|
||||||
#elif ENABLED(MESH_BED_LEVELING)
|
#elif ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
@@ -1110,13 +1157,70 @@
|
|||||||
//#define Z_SAFE_HOMING
|
//#define Z_SAFE_HOMING
|
||||||
|
|
||||||
#if ENABLED(Z_SAFE_HOMING)
|
#if ENABLED(Z_SAFE_HOMING)
|
||||||
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axes (G28).
|
||||||
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28).
|
#define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axes (G28).
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Delta only homes to Z
|
// Delta only homes to Z
|
||||||
#define HOMING_FEEDRATE_Z (200*60)
|
#define HOMING_FEEDRATE_Z (200*60)
|
||||||
|
|
||||||
|
// @section calibrate
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Bed Skew Compensation
|
||||||
|
*
|
||||||
|
* This feature corrects for misalignment in the XYZ axes.
|
||||||
|
*
|
||||||
|
* Take the following steps to get the bed skew in the XY plane:
|
||||||
|
* 1. Print a test square (e.g., https://www.thingiverse.com/thing:2563185)
|
||||||
|
* 2. For XY_DIAG_AC measure the diagonal A to C
|
||||||
|
* 3. For XY_DIAG_BD measure the diagonal B to D
|
||||||
|
* 4. For XY_SIDE_AD measure the edge A to D
|
||||||
|
*
|
||||||
|
* Marlin automatically computes skew factors from these measurements.
|
||||||
|
* Skew factors may also be computed and set manually:
|
||||||
|
*
|
||||||
|
* - Compute AB : SQRT(2*AC*AC+2*BD*BD-4*AD*AD)/2
|
||||||
|
* - XY_SKEW_FACTOR : TAN(PI/2-ACOS((AC*AC-AB*AB-AD*AD)/(2*AB*AD)))
|
||||||
|
*
|
||||||
|
* If desired, follow the same procedure for XZ and YZ.
|
||||||
|
* Use these diagrams for reference:
|
||||||
|
*
|
||||||
|
* Y Z Z
|
||||||
|
* ^ B-------C ^ B-------C ^ B-------C
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | / / | / / | / /
|
||||||
|
* | A-------D | A-------D | A-------D
|
||||||
|
* +-------------->X +-------------->X +-------------->Y
|
||||||
|
* XY_SKEW_FACTOR XZ_SKEW_FACTOR YZ_SKEW_FACTOR
|
||||||
|
*/
|
||||||
|
//#define SKEW_CORRECTION
|
||||||
|
|
||||||
|
#if ENABLED(SKEW_CORRECTION)
|
||||||
|
// Input all length measurements here:
|
||||||
|
#define XY_DIAG_AC 282.8427124746
|
||||||
|
#define XY_DIAG_BD 282.8427124746
|
||||||
|
#define XY_SIDE_AD 200
|
||||||
|
|
||||||
|
// Or, set the default skew factors directly here
|
||||||
|
// to override the above measurements:
|
||||||
|
#define XY_SKEW_FACTOR 0.0
|
||||||
|
|
||||||
|
//#define SKEW_CORRECTION_FOR_Z
|
||||||
|
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||||
|
#define XZ_DIAG_AC 282.8427124746
|
||||||
|
#define XZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_DIAG_AC 282.8427124746
|
||||||
|
#define YZ_DIAG_BD 282.8427124746
|
||||||
|
#define YZ_SIDE_AD 200
|
||||||
|
#define XZ_SKEW_FACTOR 0.0
|
||||||
|
#define YZ_SKEW_FACTOR 0.0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable this option for M852 to set skew at runtime
|
||||||
|
//#define SKEW_CORRECTION_GCODE
|
||||||
|
#endif
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//============================= Additional Features ===========================
|
//============================= Additional Features ===========================
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
@@ -1148,7 +1252,7 @@
|
|||||||
//
|
//
|
||||||
// M100 Free Memory Watcher
|
// M100 Free Memory Watcher
|
||||||
//
|
//
|
||||||
//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose
|
//#define M100_FREE_MEMORY_WATCHER // Add M100 (Free Memory Watcher) to debug memory usage
|
||||||
|
|
||||||
//
|
//
|
||||||
// G20/G21 Inch mode support
|
// G20/G21 Inch mode support
|
||||||
@@ -1293,11 +1397,11 @@
|
|||||||
*
|
*
|
||||||
* Select the language to display on the LCD. These languages are available:
|
* Select the language to display on the LCD. These languages are available:
|
||||||
*
|
*
|
||||||
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr,
|
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
|
||||||
* it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
|
||||||
* tr, uk, zh_CN, zh_TW, test
|
* tr, uk, zh_CN, zh_TW, test
|
||||||
*
|
*
|
||||||
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
|
||||||
*/
|
*/
|
||||||
#define LCD_LANGUAGE en
|
#define LCD_LANGUAGE en
|
||||||
|
|
||||||
@@ -1425,8 +1529,8 @@
|
|||||||
// Note: Test audio output with the G-Code:
|
// Note: Test audio output with the G-Code:
|
||||||
// M300 S<frequency Hz> P<duration ms>
|
// M300 S<frequency Hz> P<duration ms>
|
||||||
//
|
//
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
|
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
|
||||||
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
|
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
|
||||||
|
|
||||||
//
|
//
|
||||||
// CONTROLLER TYPE: Standard
|
// CONTROLLER TYPE: Standard
|
||||||
@@ -1534,11 +1638,13 @@
|
|||||||
//#define CARTESIO_UI
|
//#define CARTESIO_UI
|
||||||
|
|
||||||
//
|
//
|
||||||
// ANET_10 Controller supported displays.
|
// ANET and Tronxy Controller supported displays.
|
||||||
//
|
//
|
||||||
//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
|
||||||
// This LCD is known to be susceptible to electrical interference
|
// This LCD is known to be susceptible to electrical interference
|
||||||
// which scrambles the display. Pressing any button clears it up.
|
// which scrambles the display. Pressing any button clears it up.
|
||||||
|
// This is a LCD2004 display with 5 analog buttons.
|
||||||
|
|
||||||
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
|
||||||
// A clone of the RepRapDiscount full graphics display but with
|
// A clone of the RepRapDiscount full graphics display but with
|
||||||
// different pins/wiring (see pins_ANET_10.h).
|
// different pins/wiring (see pins_ANET_10.h).
|
||||||
@@ -1646,7 +1752,13 @@
|
|||||||
//
|
//
|
||||||
// Tiny, but very sharp OLED display
|
// Tiny, but very sharp OLED display
|
||||||
//
|
//
|
||||||
//#define MKS_12864OLED
|
//#define MKS_12864OLED // Uses the SH1106 controller (default)
|
||||||
|
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
|
||||||
|
|
||||||
|
// Silvergate GLCD controller
|
||||||
|
// http://github.com/android444/Silvergate
|
||||||
|
//
|
||||||
|
//#define SILVER_GATE_GLCD_CONTROLLER
|
||||||
|
|
||||||
//=============================================================================
|
//=============================================================================
|
||||||
//=============================== Extra Features ==============================
|
//=============================== Extra Features ==============================
|
||||||
@@ -1704,17 +1816,17 @@
|
|||||||
* Adds the M150 command to set the LED (or LED strip) color.
|
* Adds the M150 command to set the LED (or LED strip) color.
|
||||||
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
* If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of
|
||||||
* luminance values can be set from 0 to 255.
|
* luminance values can be set from 0 to 255.
|
||||||
* For Neopixel LED overall brightness parameters is also available
|
* For Neopixel LED an overall brightness parameter is also available.
|
||||||
*
|
*
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
|
||||||
* as the Arduino cannot handle the current the LEDs will require.
|
* as the Arduino cannot handle the current the LEDs will require.
|
||||||
* Failure to follow this precaution can destroy your Arduino!
|
* Failure to follow this precaution can destroy your Arduino!
|
||||||
* The Neopixel LED is 5V powered, but linear 5V regulator on Arduino
|
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
|
||||||
* cannot handle such current, separate 5V power supply must be used
|
* more current than the Arduino 5V linear regulator can produce.
|
||||||
* *** CAUTION ***
|
* *** CAUTION ***
|
||||||
*
|
*
|
||||||
* LED type. This options are mutualy exclusive. Uncomment only one.
|
* LED Type. Enable only one of the following two options.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
//#define RGB_LED
|
//#define RGB_LED
|
||||||
@@ -1730,11 +1842,11 @@
|
|||||||
// Support for Adafruit Neopixel LED driver
|
// Support for Adafruit Neopixel LED driver
|
||||||
//#define NEOPIXEL_LED
|
//#define NEOPIXEL_LED
|
||||||
#if ENABLED(NEOPIXEL_LED)
|
#if ENABLED(NEOPIXEL_LED)
|
||||||
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (definned in Adafruit_NeoPixel.h)
|
#define NEOPIXEL_TYPE NEO_GRBW // NEO_GRBW / NEO_GRB - four/three channel driver type (defined in Adafruit_NeoPixel.h)
|
||||||
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
#define NEOPIXEL_PIN 4 // LED driving pin on motherboard 4 => D4 (EXP2-5 on Printrboard) / 30 => PC7 (EXP3-13 on Rumba)
|
||||||
#define NEOPIXEL_PIXELS 30 // Number of LEDs on strip
|
#define NEOPIXEL_PIXELS 30 // Number of LEDs in the strip
|
||||||
#define NEOPIXEL_IS_SEQUENTIAL // Sequent display for temperature change - LED by LED. Comment out for change all LED at time
|
#define NEOPIXEL_IS_SEQUENTIAL // Sequential display for temperature change - LED by LED. Disable to change all LEDs at once.
|
||||||
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness 0-255
|
#define NEOPIXEL_BRIGHTNESS 127 // Initial brightness (0-255)
|
||||||
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
//#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
@@ -1749,22 +1861,22 @@
|
|||||||
* - Change to green once print has finished
|
* - Change to green once print has finished
|
||||||
* - Turn off after the print has finished and the user has pushed a button
|
* - Turn off after the print has finished and the user has pushed a button
|
||||||
*/
|
*/
|
||||||
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)
|
#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED)
|
||||||
#define PRINTER_EVENT_LEDS
|
#define PRINTER_EVENT_LEDS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*********************************************************************\
|
/**
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
**********************************************************************/
|
*/
|
||||||
|
|
||||||
// Number of servos
|
/**
|
||||||
//
|
* Number of servos
|
||||||
// If you select a configuration below, this will receive a default value and does not need to be set manually
|
*
|
||||||
// set it manually if you have more servos than extruders and wish to manually control some
|
* For some servo-related options NUM_SERVOS will be set automatically.
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
* Set this manually if there are extra servos needing manual control.
|
||||||
// If unsure, leave commented / disabled
|
* Leave undefined or set to 0 to entirely disable the servo subsystem.
|
||||||
//
|
*/
|
||||||
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
|
||||||
|
|
||||||
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle.
|
||||||
@@ -1777,40 +1889,4 @@
|
|||||||
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
// With this option servos are powered only during movement, then turned off to prevent jitter.
|
||||||
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
//#define DEACTIVATE_SERVOS_AFTER_MOVE
|
||||||
|
|
||||||
/**
|
|
||||||
* Filament Width Sensor
|
|
||||||
*
|
|
||||||
* Measures the filament width in real-time and adjusts
|
|
||||||
* flow rate to compensate for any irregularities.
|
|
||||||
*
|
|
||||||
* Also allows the measured filament diameter to set the
|
|
||||||
* extrusion rate, so the slicer only has to specify the
|
|
||||||
* volume.
|
|
||||||
*
|
|
||||||
* Only a single extruder is supported at this time.
|
|
||||||
*
|
|
||||||
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
|
||||||
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
|
||||||
* 301 RAMBO : Analog input 3
|
|
||||||
*
|
|
||||||
* Note: May require analog pins to be defined for other boards.
|
|
||||||
*/
|
|
||||||
//#define FILAMENT_WIDTH_SENSOR
|
|
||||||
|
|
||||||
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading.
|
|
||||||
|
|
||||||
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
|
||||||
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3)
|
|
||||||
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
|
||||||
|
|
||||||
#define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading
|
|
||||||
#define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading
|
|
||||||
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
|
||||||
|
|
||||||
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
|
||||||
|
|
||||||
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
|
||||||
//#define FILAMENT_LCD_DISPLAY
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // CONFIGURATION_H
|
#endif // CONFIGURATION_H
|
||||||
|
|||||||
@@ -32,7 +32,7 @@
|
|||||||
*/
|
*/
|
||||||
#ifndef CONFIGURATION_ADV_H
|
#ifndef CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H
|
#define CONFIGURATION_ADV_H
|
||||||
#define CONFIGURATION_ADV_H_VERSION 010100
|
#define CONFIGURATION_ADV_H_VERSION 010107
|
||||||
|
|
||||||
// @section temperature
|
// @section temperature
|
||||||
|
|
||||||
@@ -48,31 +48,36 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Thermal Protection protects your printer from damage and fire if a
|
* Thermal Protection provides additional protection to your printer from damage
|
||||||
* thermistor falls out or temperature sensors fail in any way.
|
* and fire. Marlin always includes safe min and max temperature ranges which
|
||||||
|
* protect against a broken or disconnected thermistor wire.
|
||||||
*
|
*
|
||||||
* The issue: If a thermistor falls out or a temperature sensor fails,
|
* The issue: If a thermistor falls out, it will report the much lower
|
||||||
* Marlin can no longer sense the actual temperature. Since a disconnected
|
* temperature of the air in the room, and the the firmware will keep
|
||||||
* thermistor reads as a low temperature, the firmware will keep the heater on.
|
* the heater on.
|
||||||
*
|
*
|
||||||
* The solution: Once the temperature reaches the target, start observing.
|
* The solution: Once the temperature reaches the target, start observing.
|
||||||
* If the temperature stays too far below the target (hysteresis) for too long (period),
|
* If the temperature stays too far below the target (hysteresis) for too
|
||||||
* the firmware will halt the machine as a safety precaution.
|
* 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 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
|
||||||
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
|
* Whenever an M104, M109, or M303 increases the target temperature, the
|
||||||
* WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE
|
* firmware will wait for the WATCH_TEMP_PERIOD to expire. If the temperature
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
|
* hasn't increased by WATCH_TEMP_INCREASE degrees, the machine is halted and
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
* requires a hard reset. This test restarts with any M104/M109/M303, 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
|
* If you get false positives for "Heating failed", increase WATCH_TEMP_PERIOD
|
||||||
* WATCH_TEMP_INCREASE should not be below 2.
|
* and/or decrease WATCH_TEMP_INCREASE. WATCH_TEMP_INCREASE should not be set
|
||||||
|
* below 2.
|
||||||
*/
|
*/
|
||||||
#define WATCH_TEMP_PERIOD 20 // Seconds
|
#define WATCH_TEMP_PERIOD 20 // Seconds
|
||||||
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -86,13 +91,7 @@
|
|||||||
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
|
* As described above, except for the bed (M140/M190/M303).
|
||||||
* WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE
|
|
||||||
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
|
|
||||||
* but only if the current temperature is far enough below the target for a reliable test.
|
|
||||||
*
|
|
||||||
* If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease
|
|
||||||
* WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.)
|
|
||||||
*/
|
*/
|
||||||
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
|
||||||
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
|
||||||
@@ -123,6 +122,9 @@
|
|||||||
#define AUTOTEMP_OLDWEIGHT 0.98
|
#define AUTOTEMP_OLDWEIGHT 0.98
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Show extra position information in M114
|
||||||
|
//#define M114_DETAIL
|
||||||
|
|
||||||
// Show Temperature ADC value
|
// Show Temperature ADC value
|
||||||
// Enable for M105 to include ADC values read from temperature sensors.
|
// Enable for M105 to include ADC values read from temperature sensors.
|
||||||
//#define SHOW_TEMP_ADC_VALUES
|
//#define SHOW_TEMP_ADC_VALUES
|
||||||
@@ -257,48 +259,49 @@
|
|||||||
|
|
||||||
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
|
||||||
|
|
||||||
// Dual X Steppers
|
/**
|
||||||
// Uncomment this option to drive two X axis motors.
|
* Dual Steppers / Dual Endstops
|
||||||
// The next unused E driver will be assigned to the second X stepper.
|
*
|
||||||
|
* This section will allow you to use extra E drivers to drive a second motor for X, Y, or Z axes.
|
||||||
|
*
|
||||||
|
* For example, set X_DUAL_STEPPER_DRIVERS setting to use a second motor. If the motors need to
|
||||||
|
* spin in opposite directions set INVERT_X2_VS_X_DIR. If the second motor needs its own endstop
|
||||||
|
* set X_DUAL_ENDSTOPS. This can adjust for "racking." Use X2_USE_ENDSTOP to set the endstop plug
|
||||||
|
* that should be used for the second endstop. Extra endstops will appear in the output of 'M119'.
|
||||||
|
*
|
||||||
|
* Use X_DUAL_ENDSTOP_ADJUSTMENT to adjust for mechanical imperfection. After homing both motors
|
||||||
|
* this offset is applied to the X2 motor. To find the offset home the X axis, and measure the error
|
||||||
|
* in X2. Dual endstop offsets can be set at runtime with 'M666 X<offset> Y<offset> Z<offset>'.
|
||||||
|
*/
|
||||||
|
|
||||||
//#define X_DUAL_STEPPER_DRIVERS
|
//#define X_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two X motors need to rotate in opposite directions
|
#define INVERT_X2_VS_X_DIR true // Set 'true' if X motors should rotate in opposite directions
|
||||||
#define INVERT_X2_VS_X_DIR true
|
//#define X_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||||
|
#define X2_USE_ENDSTOP _XMAX_
|
||||||
|
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Dual Y Steppers
|
|
||||||
// Uncomment this option to drive two Y axis motors.
|
|
||||||
// The next unused E driver will be assigned to the second Y stepper.
|
|
||||||
//#define Y_DUAL_STEPPER_DRIVERS
|
//#define Y_DUAL_STEPPER_DRIVERS
|
||||||
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
|
||||||
// Set true if the two Y motors need to rotate in opposite directions
|
#define INVERT_Y2_VS_Y_DIR true // Set 'true' if Y motors should rotate in opposite directions
|
||||||
#define INVERT_Y2_VS_Y_DIR true
|
//#define Y_DUAL_ENDSTOPS
|
||||||
|
#if ENABLED(Y_DUAL_ENDSTOPS)
|
||||||
|
#define Y2_USE_ENDSTOP _YMAX_
|
||||||
|
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// A single Z stepper driver is usually used to drive 2 stepper motors.
|
|
||||||
// Uncomment this option to use a separate stepper driver for each Z axis motor.
|
|
||||||
// The next unused E driver will be assigned to the second Z stepper.
|
|
||||||
//#define Z_DUAL_STEPPER_DRIVERS
|
//#define Z_DUAL_STEPPER_DRIVERS
|
||||||
|
|
||||||
#if ENABLED(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
|
//#define Z_DUAL_ENDSTOPS
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
#define Z2_USE_ENDSTOP _XMAX_
|
#define Z2_USE_ENDSTOP _XMAX_
|
||||||
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value
|
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
#endif // Z_DUAL_STEPPER_DRIVERS
|
|
||||||
|
|
||||||
// Enable this for dual x-carriage printers.
|
// Enable this for dual x-carriage printers.
|
||||||
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
@@ -345,12 +348,12 @@
|
|||||||
|
|
||||||
// @section homing
|
// @section homing
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
// Homing hits each endstop, retracts by these distances, then does a slower bump.
|
||||||
#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 5 // deltas need the same for all three axes
|
#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes
|
||||||
#define HOMING_BUMP_DIVISOR {10, 10, 10} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
|
#define HOMING_BUMP_DIVISOR { 10, 10, 10 } // 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 homing includes X and Y, do a diagonal move 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
|
||||||
@@ -436,8 +439,21 @@
|
|||||||
//#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)
|
||||||
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
|
||||||
|
|
||||||
// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
|
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
|
||||||
//#define DIGIPOT_I2C
|
//#define DIGIPOT_I2C
|
||||||
|
#if ENABLED(DIGIPOT_I2C) && !defined(DIGIPOT_I2C_ADDRESS_A)
|
||||||
|
/**
|
||||||
|
* Common slave addresses:
|
||||||
|
*
|
||||||
|
* A (A shifted) B (B shifted) IC
|
||||||
|
* Smoothie 0x2C (0x58) 0x2D (0x5A) MCP4451
|
||||||
|
* AZTEEG_X3_PRO 0x2C (0x58) 0x2E (0x5C) MCP4451
|
||||||
|
* MIGHTYBOARD_REVE 0x2F (0x5E) MCP4018
|
||||||
|
*/
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_A 0x2C // unshifted slave address for first DIGIPOT
|
||||||
|
#define DIGIPOT_I2C_ADDRESS_B 0x2D // unshifted slave address for second DIGIPOT
|
||||||
|
#endif
|
||||||
|
|
||||||
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
|
||||||
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
|
||||||
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
|
||||||
@@ -468,6 +484,23 @@
|
|||||||
// The timeout (in ms) to return to the status screen from sub-menus
|
// The timeout (in ms) to return to the status screen from sub-menus
|
||||||
//#define LCD_TIMEOUT_TO_STATUS 15000
|
//#define LCD_TIMEOUT_TO_STATUS 15000
|
||||||
|
|
||||||
|
/**
|
||||||
|
* LED Control Menu
|
||||||
|
* Enable this feature to add LED Control to the LCD menu
|
||||||
|
*/
|
||||||
|
//#define LED_CONTROL_MENU
|
||||||
|
#if ENABLED(LED_CONTROL_MENU)
|
||||||
|
#define LED_COLOR_PRESETS // Enable the Preset Color menu option
|
||||||
|
#if ENABLED(LED_COLOR_PRESETS)
|
||||||
|
#define LED_USER_PRESET_RED 255 // User defined RED value
|
||||||
|
#define LED_USER_PRESET_GREEN 128 // User defined GREEN value
|
||||||
|
#define LED_USER_PRESET_BLUE 0 // User defined BLUE value
|
||||||
|
#define LED_USER_PRESET_WHITE 255 // User defined WHITE value
|
||||||
|
#define LED_USER_PRESET_BRIGHTNESS 255 // User defined intensity
|
||||||
|
//#define LED_USER_PRESET_STARTUP // Have the printer display the user preset color on startup
|
||||||
|
#endif
|
||||||
|
#endif // LED_CONTROL_MENU
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
|
||||||
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
|
||||||
@@ -477,12 +510,14 @@
|
|||||||
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
|
||||||
#define SD_DETECT_INVERTED
|
#define SD_DETECT_INVERTED
|
||||||
|
|
||||||
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
|
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
|
||||||
#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.
|
||||||
|
|
||||||
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
|
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
|
||||||
// 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.
|
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
|
||||||
// using:
|
#define SDCARD_RATHERRECENTFIRST
|
||||||
|
|
||||||
|
// Add an option in the menu to run all auto#.g files
|
||||||
//#define MENU_ADDAUTOSTART
|
//#define MENU_ADDAUTOSTART
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -519,6 +554,8 @@
|
|||||||
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
#define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.)
|
||||||
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
#define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option.
|
||||||
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
#define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use!
|
||||||
|
#define SDSORT_CACHE_VFATS 2 // Maximum number of 13-byte VFAT entries to use for sorting.
|
||||||
|
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Show a progress bar on HD44780 LCDs for SD printing
|
// Show a progress bar on HD44780 LCDs for SD printing
|
||||||
@@ -537,14 +574,29 @@
|
|||||||
//#define LCD_PROGRESS_BAR_TEST
|
//#define LCD_PROGRESS_BAR_TEST
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Add an 'M73' G-code to set the current percentage
|
||||||
|
//#define LCD_SET_PROGRESS_MANUALLY
|
||||||
|
|
||||||
// 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.
|
// Enable this option to scroll long filenames in the SD card menu
|
||||||
// This feature must be enabled with "M540 S1" or from the LCD menu.
|
//#define SCROLL_LONG_FILENAMES
|
||||||
// To have any effect, endstops must be enabled during SD printing.
|
|
||||||
|
/**
|
||||||
|
* 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.
|
||||||
|
*/
|
||||||
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This option makes it easier to print the same SD Card file again.
|
||||||
|
* On print completion the LCD Menu will open with the file selected.
|
||||||
|
* You can just click to start the print, or navigate elsewhere.
|
||||||
|
*/
|
||||||
|
//#define SD_REPRINT_LAST_SELECTED_FILE
|
||||||
|
|
||||||
#endif // SDSUPPORT
|
#endif // SDSUPPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -577,6 +629,10 @@
|
|||||||
// Enable this option and reduce the value to optimize screen updates.
|
// Enable this option and reduce the value to optimize screen updates.
|
||||||
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
|
||||||
//#define DOGM_SPI_DELAY_US 5
|
//#define DOGM_SPI_DELAY_US 5
|
||||||
|
|
||||||
|
// Swap the CW/CCW indicators in the graphics overlay
|
||||||
|
//#define OVERLAY_GFX_REVERSE
|
||||||
|
|
||||||
#endif // DOGLCD
|
#endif // DOGLCD
|
||||||
|
|
||||||
// @section safety
|
// @section safety
|
||||||
@@ -605,13 +661,12 @@
|
|||||||
#if ENABLED(BABYSTEPPING)
|
#if ENABLED(BABYSTEPPING)
|
||||||
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
|
||||||
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
|
||||||
#define BABYSTEP_MULTIPLICATOR 100 // Babysteps are very small. Increase for faster motion.
|
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
|
||||||
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
|
||||||
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
|
||||||
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
|
||||||
// Note: Extra time may be added to mitigate controller latency.
|
// Note: Extra time may be added to mitigate controller latency.
|
||||||
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
|
||||||
//#define BABYSTEP_ZPROBE_GFX_REVERSE // Reverses the direction of the CW/CCW indicators
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extruder
|
// @section extruder
|
||||||
@@ -658,23 +713,18 @@
|
|||||||
|
|
||||||
// @section leveling
|
// @section leveling
|
||||||
|
|
||||||
// Default mesh area is an area with an inset margin on the print area.
|
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
|
||||||
// Below are the macros that are used to define the borders for the mesh area,
|
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
|
||||||
// made available here for specialized needs, ie dual extruder setup.
|
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
|
||||||
#define MESH_MIN_X MESH_INSET
|
#endif
|
||||||
#define MESH_MAX_X (X_BED_SIZE - (MESH_INSET))
|
|
||||||
#define MESH_MIN_Y MESH_INSET
|
|
||||||
#define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET))
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#define UBL_MESH_MIN_X UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
#define UBL_MESH_MIN_Y UBL_MESH_INSET
|
|
||||||
#define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET))
|
|
||||||
|
|
||||||
// If this is defined, the currently active mesh will be saved in the
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
// current slot on M500.
|
// Override the mesh area if the automatic (max) area is too large
|
||||||
#define UBL_SAVE_ACTIVE_ON_M500
|
//#define MESH_MIN_X MESH_INSET
|
||||||
|
//#define MESH_MIN_Y MESH_INSET
|
||||||
|
//#define MESH_MAX_X X_BED_SIZE - (MESH_INSET)
|
||||||
|
//#define MESH_MAX_Y Y_BED_SIZE - (MESH_INSET)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section extras
|
// @section extras
|
||||||
@@ -694,7 +744,7 @@
|
|||||||
//#define BEZIER_CURVE_SUPPORT
|
//#define BEZIER_CURVE_SUPPORT
|
||||||
|
|
||||||
// G38.2 and G38.3 Probe Target
|
// G38.2 and G38.3 Probe Target
|
||||||
// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch
|
// Set MULTIPLE_PROBING if you want G38 to double touch
|
||||||
//#define G38_PROBE_TARGET
|
//#define G38_PROBE_TARGET
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
#define G38_MINIMUM_MOVE 0.0275 // minimum distance in mm that will produce a move (determined using the print statement in check_move)
|
||||||
@@ -719,7 +769,7 @@
|
|||||||
// @section hidden
|
// @section hidden
|
||||||
|
|
||||||
// The number of linear motions that can be in the plan at any give time.
|
// 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.
|
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
|
||||||
#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
|
||||||
@@ -809,6 +859,15 @@
|
|||||||
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
#define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extra Fan Speed
|
||||||
|
* Adds a secondary fan speed for each print-cooling fan.
|
||||||
|
* 'M106 P<fan> T3-255' : Set a secondary speed for <fan>
|
||||||
|
* 'M106 P<fan> T2' : Use the set secondary speed
|
||||||
|
* 'M106 P<fan> T1' : Restore the previous fan speed
|
||||||
|
*/
|
||||||
|
//#define EXTRA_FAN_SPEED
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Advanced Pause
|
* Advanced Pause
|
||||||
* Experimental feature for filament change support and for parking the nozzle when paused.
|
* Experimental feature for filament change support and for parking the nozzle when paused.
|
||||||
@@ -919,7 +978,7 @@
|
|||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @section TMC2130
|
// @section TMC2130, TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
|
||||||
@@ -933,7 +992,19 @@
|
|||||||
*/
|
*/
|
||||||
//#define HAVE_TMC2130
|
//#define HAVE_TMC2130
|
||||||
|
|
||||||
#if ENABLED(HAVE_TMC2130)
|
/**
|
||||||
|
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
|
||||||
|
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
|
||||||
|
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
|
||||||
|
* to #_SERIAL_TX_PIN with a 1K resistor.
|
||||||
|
* The drivers can also be used with hardware serial.
|
||||||
|
*
|
||||||
|
* You'll also need the TMC2208Stepper Arduino library
|
||||||
|
* (https://github.com/teemuatlut/TMC2208Stepper).
|
||||||
|
*/
|
||||||
|
//#define HAVE_TMC2208
|
||||||
|
|
||||||
|
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
|
||||||
|
|
||||||
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
|
||||||
//#define X_IS_TMC2130
|
//#define X_IS_TMC2130
|
||||||
@@ -948,46 +1019,58 @@
|
|||||||
//#define E3_IS_TMC2130
|
//#define E3_IS_TMC2130
|
||||||
//#define E4_IS_TMC2130
|
//#define E4_IS_TMC2130
|
||||||
|
|
||||||
|
//#define X_IS_TMC2208
|
||||||
|
//#define X2_IS_TMC2208
|
||||||
|
//#define Y_IS_TMC2208
|
||||||
|
//#define Y2_IS_TMC2208
|
||||||
|
//#define Z_IS_TMC2208
|
||||||
|
//#define Z2_IS_TMC2208
|
||||||
|
//#define E0_IS_TMC2208
|
||||||
|
//#define E1_IS_TMC2208
|
||||||
|
//#define E2_IS_TMC2208
|
||||||
|
//#define E3_IS_TMC2208
|
||||||
|
//#define E4_IS_TMC2208
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Stepper driver settings
|
* Stepper driver settings
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
|
||||||
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
|
||||||
#define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256
|
#define INTERPOLATE true // Interpolate X/Y/Z_MICROSTEPS to 256
|
||||||
|
|
||||||
#define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current.
|
#define X_CURRENT 800 // rms current in mA. Multiply by 1.41 for peak current.
|
||||||
#define X_MICROSTEPS 16 // 0..256
|
#define X_MICROSTEPS 16 // 0..256
|
||||||
|
|
||||||
#define Y_CURRENT 1000
|
#define Y_CURRENT 800
|
||||||
#define Y_MICROSTEPS 16
|
#define Y_MICROSTEPS 16
|
||||||
|
|
||||||
#define Z_CURRENT 1000
|
#define Z_CURRENT 800
|
||||||
#define Z_MICROSTEPS 16
|
#define Z_MICROSTEPS 16
|
||||||
|
|
||||||
//#define X2_CURRENT 1000
|
#define X2_CURRENT 800
|
||||||
//#define X2_MICROSTEPS 16
|
#define X2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Y2_CURRENT 1000
|
#define Y2_CURRENT 800
|
||||||
//#define Y2_MICROSTEPS 16
|
#define Y2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define Z2_CURRENT 1000
|
#define Z2_CURRENT 800
|
||||||
//#define Z2_MICROSTEPS 16
|
#define Z2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E0_CURRENT 1000
|
#define E0_CURRENT 800
|
||||||
//#define E0_MICROSTEPS 16
|
#define E0_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E1_CURRENT 1000
|
#define E1_CURRENT 800
|
||||||
//#define E1_MICROSTEPS 16
|
#define E1_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E2_CURRENT 1000
|
#define E2_CURRENT 800
|
||||||
//#define E2_MICROSTEPS 16
|
#define E2_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E3_CURRENT 1000
|
#define E3_CURRENT 800
|
||||||
//#define E3_MICROSTEPS 16
|
#define E3_MICROSTEPS 16
|
||||||
|
|
||||||
//#define E4_CURRENT 1000
|
#define E4_CURRENT 800
|
||||||
//#define E4_MICROSTEPS 16
|
#define E4_MICROSTEPS 16
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Use Trinamic's ultra quiet stepping mode.
|
* Use Trinamic's ultra quiet stepping mode.
|
||||||
@@ -996,24 +1079,22 @@
|
|||||||
#define STEALTHCHOP
|
#define STEALTHCHOP
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Let Marlin automatically control stepper current.
|
* Monitor Trinamic TMC2130 and TMC2208 drivers for error conditions,
|
||||||
* This is still an experimental feature.
|
* like overtemperature and short to ground. TMC2208 requires hardware serial.
|
||||||
* Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered,
|
* In the case of overtemperature Marlin can decrease the driver current until error condition clears.
|
||||||
* then decrease current by CURRENT_STEP until temperature prewarn is cleared.
|
* Other detected conditions can be used to stop the current print.
|
||||||
* Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX
|
|
||||||
* Relevant g-codes:
|
* Relevant g-codes:
|
||||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given.
|
||||||
* M906 S1 - Start adjusting current
|
|
||||||
* M906 S0 - Stop adjusting current
|
|
||||||
* M911 - Report stepper driver overtemperature pre-warn condition.
|
* M911 - Report stepper driver overtemperature pre-warn condition.
|
||||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
* M912 - Clear stepper driver overtemperature pre-warn condition flag.
|
||||||
|
* M122 S0/1 - Report driver parameters (Requires TMC_DEBUG)
|
||||||
*/
|
*/
|
||||||
//#define AUTOMATIC_CURRENT_CONTROL
|
//#define MONITOR_DRIVER_STATUS
|
||||||
|
|
||||||
#if ENABLED(AUTOMATIC_CURRENT_CONTROL)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
#define CURRENT_STEP 50 // [mA]
|
#define CURRENT_STEP_DOWN 50 // [mA]
|
||||||
#define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak
|
|
||||||
#define REPORT_CURRENT_CHANGE
|
#define REPORT_CURRENT_CHANGE
|
||||||
|
#define STOP_ON_ERROR
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -1028,8 +1109,8 @@
|
|||||||
#define X2_HYBRID_THRESHOLD 100
|
#define X2_HYBRID_THRESHOLD 100
|
||||||
#define Y_HYBRID_THRESHOLD 100
|
#define Y_HYBRID_THRESHOLD 100
|
||||||
#define Y2_HYBRID_THRESHOLD 100
|
#define Y2_HYBRID_THRESHOLD 100
|
||||||
#define Z_HYBRID_THRESHOLD 4
|
#define Z_HYBRID_THRESHOLD 3
|
||||||
#define Z2_HYBRID_THRESHOLD 4
|
#define Z2_HYBRID_THRESHOLD 3
|
||||||
#define E0_HYBRID_THRESHOLD 30
|
#define E0_HYBRID_THRESHOLD 30
|
||||||
#define E1_HYBRID_THRESHOLD 30
|
#define E1_HYBRID_THRESHOLD 30
|
||||||
#define E2_HYBRID_THRESHOLD 30
|
#define E2_HYBRID_THRESHOLD 30
|
||||||
@@ -1039,7 +1120,7 @@
|
|||||||
/**
|
/**
|
||||||
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
* Use stallGuard2 to sense an obstacle and trigger an endstop.
|
||||||
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
|
||||||
* If used along with STEALTHCHOP, the movement will be louder when homing. This is normal.
|
* X and Y homing will always be done in spreadCycle mode.
|
||||||
*
|
*
|
||||||
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
|
||||||
* Higher values make the system LESS sensitive.
|
* Higher values make the system LESS sensitive.
|
||||||
@@ -1048,27 +1129,34 @@
|
|||||||
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
* It is advised to set X/Y_HOME_BUMP_MM to 0.
|
||||||
* M914 X/Y to live tune the setting
|
* M914 X/Y to live tune the setting
|
||||||
*/
|
*/
|
||||||
//#define SENSORLESS_HOMING
|
//#define SENSORLESS_HOMING // TMC2130 only
|
||||||
|
|
||||||
#if ENABLED(SENSORLESS_HOMING)
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
#define X_HOMING_SENSITIVITY 19
|
#define X_HOMING_SENSITIVITY 8
|
||||||
#define Y_HOMING_SENSITIVITY 19
|
#define Y_HOMING_SENSITIVITY 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable M122 debugging command for TMC stepper drivers.
|
||||||
|
* M122 S0/1 will enable continous reporting.
|
||||||
|
*/
|
||||||
|
//#define TMC_DEBUG
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* You can set your own advanced settings by filling in predefined functions.
|
* You can set your own advanced settings by filling in predefined functions.
|
||||||
* A list of available functions can be found on the library github page
|
* A list of available functions can be found on the library github page
|
||||||
* https://github.com/teemuatlut/TMC2130Stepper
|
* https://github.com/teemuatlut/TMC2130Stepper
|
||||||
|
* https://github.com/teemuatlut/TMC2208Stepper
|
||||||
*
|
*
|
||||||
* Example:
|
* Example:
|
||||||
* #define TMC2130_ADV() { \
|
* #define TMC_ADV() { \
|
||||||
* stepperX.diag0_temp_prewarn(1); \
|
* stepperX.diag0_temp_prewarn(1); \
|
||||||
* stepperX.interpolate(0); \
|
* stepperY.interpolate(0); \
|
||||||
* }
|
* }
|
||||||
*/
|
*/
|
||||||
#define TMC2130_ADV() { }
|
#define TMC_ADV() { }
|
||||||
|
|
||||||
#endif // HAVE_TMC2130
|
#endif // TMC2130 || TMC2208
|
||||||
|
|
||||||
// @section L6470
|
// @section L6470
|
||||||
|
|
||||||
@@ -1232,6 +1320,47 @@
|
|||||||
//#define SPEED_POWER_MAX 100 // 0-100%
|
//#define SPEED_POWER_MAX 100 // 0-100%
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Filament Width Sensor
|
||||||
|
*
|
||||||
|
* Measures the filament width in real-time and adjusts
|
||||||
|
* flow rate to compensate for any irregularities.
|
||||||
|
*
|
||||||
|
* Also allows the measured filament diameter to set the
|
||||||
|
* extrusion rate, so the slicer only has to specify the
|
||||||
|
* volume.
|
||||||
|
*
|
||||||
|
* Only a single extruder is supported at this time.
|
||||||
|
*
|
||||||
|
* 34 RAMPS_14 : Analog input 5 on the AUX2 connector
|
||||||
|
* 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E)
|
||||||
|
* 301 RAMBO : Analog input 3
|
||||||
|
*
|
||||||
|
* Note: May require analog pins to be defined for other boards.
|
||||||
|
*/
|
||||||
|
//#define FILAMENT_WIDTH_SENSOR
|
||||||
|
|
||||||
|
#if ENABLED(FILAMENT_WIDTH_SENSOR)
|
||||||
|
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor. :[0,1,2,3,4]
|
||||||
|
#define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber
|
||||||
|
|
||||||
|
#define FILWIDTH_ERROR_MARGIN 1.0 // (mm) If a measurement differs too much from nominal width ignore it
|
||||||
|
#define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM.
|
||||||
|
|
||||||
|
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially
|
||||||
|
|
||||||
|
// Display filament width on the LCD status line. Status messages will expire after 5 seconds.
|
||||||
|
//#define FILAMENT_LCD_DISPLAY
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* CNC Coordinate Systems
|
||||||
|
*
|
||||||
|
* Enables G53 and G54-G59.3 commands to select coordinate systems
|
||||||
|
* and G92.1 to reset the workspace to native machine space.
|
||||||
|
*/
|
||||||
|
//#define CNC_COORDINATE_SYSTEMS
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
* M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||||
*/
|
*/
|
||||||
@@ -1248,13 +1377,20 @@
|
|||||||
#define EXTENDED_CAPABILITIES_REPORT
|
#define EXTENDED_CAPABILITIES_REPORT
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
* Disable all Volumetric extrusion options
|
||||||
|
*/
|
||||||
|
//#define NO_VOLUMETRICS
|
||||||
|
|
||||||
|
#if DISABLED(NO_VOLUMETRICS)
|
||||||
|
/**
|
||||||
* Volumetric extrusion default state
|
* Volumetric extrusion default state
|
||||||
* Activate to make volumetric extrusion the default method,
|
* Activate to make volumetric extrusion the default method,
|
||||||
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
* with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter.
|
||||||
*
|
*
|
||||||
* M200 D0 to disable, M200 Dn to set a new diameter.
|
* M200 D0 to disable, M200 Dn to set a new diameter.
|
||||||
*/
|
*/
|
||||||
//#define VOLUMETRIC_DEFAULT_ON
|
//#define VOLUMETRIC_DEFAULT_ON
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Enable this option for a leaner build of Marlin that removes all
|
* Enable this option for a leaner build of Marlin that removes all
|
||||||
@@ -1423,4 +1559,17 @@
|
|||||||
// tweaks made to the configuration are affecting the printer in real-time.
|
// tweaks made to the configuration are affecting the printer in real-time.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* NanoDLP Sync support
|
||||||
|
*
|
||||||
|
* Add support for Synchronized Z moves when using with NanoDLP. G0/G1 axis moves will output "Z_move_comp"
|
||||||
|
* string to enable synchronization with DLP projector exposure. This change will allow to use
|
||||||
|
* [[WaitForDoneMessage]] instead of populating your gcode with M400 commands
|
||||||
|
*/
|
||||||
|
//#define NANODLP_Z_SYNC
|
||||||
|
#if ENABLED(NANODLP_Z_SYNC)
|
||||||
|
//#define NANODLP_ALL_AXIS // Enables "Z_move_comp" output on any axis move.
|
||||||
|
// Default behaviour is limited to Z axis only.
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // CONFIGURATION_ADV_H
|
#endif // CONFIGURATION_ADV_H
|
||||||
|
|||||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user