Merge branch 'RCBugFix' into RC

This commit is contained in:
Scott Lahteine
2016-12-06 00:44:59 -06:00
192 changed files with 31487 additions and 15841 deletions

4
.gitignore vendored Normal file → Executable file
View File

@@ -114,3 +114,7 @@ applet/
# Debug files
*.dSYM/
*.su
#PlatformIO files/dirs
.pioenvs
.piolib

View File

@@ -20,10 +20,10 @@ before_install:
#
install:
#
# Install arduino 1.6.9
- wget http://downloads-02.arduino.cc/arduino-1.6.9-linux64.tar.xz
- tar xf arduino-1.6.9-linux64.tar.xz
- sudo mv arduino-1.6.9 /usr/local/share/arduino
# Install arduino 1.6.10
- wget http://downloads-02.arduino.cc/arduino-1.6.10-linux64.tar.xz
- tar xf arduino-1.6.10-linux64.tar.xz
- sudo mv arduino-1.6.10 /usr/local/share/arduino
- ln -s /usr/local/share/arduino/arduino ${TRAVIS_BUILD_DIR}/buildroot/bin/arduino
#
# Install: LiquidCrystal_I2C library
@@ -35,15 +35,20 @@ install:
- sudo mv LiquidTWI2 /usr/local/share/arduino/libraries/LiquidTWI2
#
# Install: Monochrome Graphics Library for LCDs and OLEDs
- arduino --install-library "U8glib"
- git clone https://github.com/olikraus/U8glib_Arduino.git
- sudo mv U8glib_Arduino /usr/local/share/arduino/libraries/U8glib
#
# Install: L6470 Stepper Motor Driver library
- git clone https://github.com/ameyer/Arduino-L6470.git
- sudo mv Arduino-L6470/L6470 /usr/local/share/arduino/libraries/L6470
# - git clone https://github.com/ameyer/Arduino-L6470.git
# - sudo mv Arduino-L6470/L6470 /usr/local/share/arduino/libraries/L6470
#
# Install: TMC26X Stepper Motor Controller library
- git clone https://github.com/trinamic/TMC26XStepper.git
- sudo mv TMC26XStepper /usr/local/share/arduino/libraries/TMC26XStepper
# - git clone https://github.com/trinamic/TMC26XStepper.git
# - sudo mv TMC26XStepper /usr/local/share/arduino/libraries/TMC26XStepper
#
# Install: TMC2130 Stepper Motor Controller library
- git clone https://github.com/MarlinFirmware/Trinamic_TMC2130.git
- sudo mv Trinamic_TMC2130/Trinamic_TMC2130 /usr/local/share/arduino/libraries/Trinamic_TMC2130
#
before_script:
#
@@ -93,15 +98,23 @@ script:
- opt_enable PIDTEMPBED
- build_marlin
#
# Test MAX6675
#
- restore_configs
- opt_set TEMP_SENSOR_0 -2
- build_marlin
#
# Test a "Fix Mounted" Probe along with Safe Homing
#
- restore_configs
- opt_enable FIX_MOUNTED_PROBE Z_SAFE_HOMING
- build_marlin
#
# ...with AUTO_BED_LEVELING_FEATURE, Z_MIN_PROBE_REPEATABILITY_TEST, & DEBUG_LEVELING_FEATURE
# ...with AUTO_BED_LEVELING_LINEAR, Z_MIN_PROBE_REPEATABILITY_TEST, and DEBUG_LEVELING_FEATURE
#
- opt_enable AUTO_BED_LEVELING_FEATURE Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE
- opt_enable AUTO_BED_LEVELING_LINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE
- opt_set ABL_GRID_POINTS_X 16
- opt_set ABL_GRID_POINTS_Y 16
- build_marlin
#
# Test a Sled Z Probe
@@ -110,9 +123,9 @@ script:
- opt_enable Z_PROBE_SLED
- build_marlin
#
# ...with AUTO_BED_LEVELING_FEATURE & DEBUG_LEVELING_FEATURE
# ...with AUTO_BED_LEVELING_LINEAR, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, and EEPROM_CHITCHAT
#
- opt_enable AUTO_BED_LEVELING_FEATURE DEBUG_LEVELING_FEATURE
- opt_enable AUTO_BED_LEVELING_LINEAR DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT
- build_marlin
#
# Test a Servo Probe
@@ -121,9 +134,10 @@ script:
- opt_enable NUM_SERVOS Z_ENDSTOP_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE
- build_marlin
#
# ...with AUTO_BED_LEVELING_FEATURE & DEBUG_LEVELING_FEATURE
# ...with AUTO_BED_LEVELING_3POINT, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, EEPROM_CHITCHAT, EXTENDED_CAPABILITIES_REPORT, and AUTO_REPORT_TEMPERATURES
#
- opt_enable AUTO_BED_LEVELING_FEATURE DEBUG_LEVELING_FEATURE
- opt_enable AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT
- opt_enable_adv EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES
- build_marlin
#
# Test MESH_BED_LEVELING feature, with LCD
@@ -199,10 +213,11 @@ script:
- opt_enable ULTIMAKERCONTROLLER FILAMENT_LCD_DISPLAY
- build_marlin
#
# Enable BEZIER_CURVE_SUPPORT
# Enable BEZIER_CURVE_SUPPORT, EXPERIMENTAL_I2CBUS, and I2C_SLAVE_ADDRESS
#
- restore_configs
- opt_enable_adv BEZIER_CURVE_SUPPORT
- opt_enable_adv BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS
- opt_set_adv I2C_SLAVE_ADDRESS 63
- build_marlin
#
# Enable COREXY
@@ -343,13 +358,14 @@ script:
# Delta Config (generic)
- restore_configs
- use_example_configs delta/generic
- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER DELTA_CALIBRATION_MENU
- build_marlin
#
# Delta Config (generic) + ABL + ALLEN_KEY
#
- use_example_configs delta/generic
- opt_disable DISABLE_MIN_ENDSTOPS
- opt_enable AUTO_BED_LEVELING_FEATURE Z_PROBE_ALLEN_KEY
- opt_enable AUTO_BED_LEVELING_BILINEAR Z_PROBE_ALLEN_KEY
- build_marlin
#
# Delta Config (Mini Kossel)
@@ -365,7 +381,13 @@ script:
# SCARA Config
#
- use_example_configs SCARA
- opt_enable AUTO_BED_LEVELING_FEATURE FIX_MOUNTED_PROBE USE_ZMIN_PLUG
- opt_enable AUTO_BED_LEVELING_BILINEAR FIX_MOUNTED_PROBE USE_ZMIN_PLUG EEPROM_SETTINGS EEPROM_CHITCHAT ULTIMAKERCONTROLLER
- build_marlin
#
# TMC2130 Config
#
- restore_configs
- opt_enable_adv HAVE_TMC2130DRIVER X_IS_TMC2130 Y_IS_TMC2130 Z_IS_TMC2130 E0_IS_TMC2130
- build_marlin
#
# tvrrug Config need to check board type for sanguino atmega644p

View File

@@ -22,7 +22,7 @@
/**
* Conditionals_LCD.h
* LCD Defines that depend on configuration but are not editable.
* Conditionals that need to be set before Configuration_adv.h or pins.h
*/
#ifndef CONDITIONALS_LCD_H // Get the LCD defines which are needed first
@@ -286,7 +286,7 @@
* HOTENDS - Number of hotends, whether connected or separate
* E_STEPPERS - Number of actual E stepper motors
* TOOL_E_INDEX - Index to use when getting/setting the tool state
*
*
*/
#if ENABLED(SINGLENOZZLE) // One hotend, multi-extruder
#define HOTENDS 1
@@ -316,4 +316,66 @@
#define TOOL_E_INDEX current_block->active_extruder
#endif
/**
* Distinct E Factors Disable by commenting out DISTINCT_E_FACTORS
*/
#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1
#define XYZE_N (XYZ + E_STEPPERS)
#define E_AXIS_N (E_AXIS + extruder)
#else
#undef DISTINCT_E_FACTORS
#define XYZE_N XYZE
#define E_AXIS_N E_AXIS
#endif
/**
* The BLTouch Probe emulates a servo probe
* and uses "special" angles for its state.
*/
#if ENABLED(BLTOUCH)
#ifndef Z_ENDSTOP_SERVO_NR
#define Z_ENDSTOP_SERVO_NR 0
#endif
#ifndef NUM_SERVOS
#define NUM_SERVOS (Z_ENDSTOP_SERVO_NR + 1)
#endif
#undef DEACTIVATE_SERVOS_AFTER_MOVE
#undef SERVO_DELAY
#define SERVO_DELAY 50
#undef Z_SERVO_ANGLES
#define Z_SERVO_ANGLES { BLTOUCH_DEPLOY, BLTOUCH_STOW }
#define BLTOUCH_DEPLOY 10
#define BLTOUCH_STOW 90
#define BLTOUCH_SELFTEST 120
#define BLTOUCH_RESET 160
#define _TEST_BLTOUCH(P) (READ(P##_PIN) != P##_ENDSTOP_INVERTING)
#if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
#undef Z_MIN_ENDSTOP_INVERTING
#define Z_MIN_ENDSTOP_INVERTING false
#define TEST_BLTOUCH() _TEST_BLTOUCH(Z_MIN)
#else
#define TEST_BLTOUCH() _TEST_BLTOUCH(Z_MIN_PROBE)
#endif
#endif
/**
* Set a flag for a servo probe
*/
#define HAS_Z_SERVO_ENDSTOP (defined(Z_ENDSTOP_SERVO_NR) && Z_ENDSTOP_SERVO_NR >= 0)
/**
* Set a flag for any enabled probe
*/
#define PROBE_SELECTED (ENABLED(FIX_MOUNTED_PROBE) || ENABLED(Z_PROBE_ALLEN_KEY) || HAS_Z_SERVO_ENDSTOP || ENABLED(Z_PROBE_SLED))
/**
* Clear probe pin settings when no probe is selected
*/
#if !PROBE_SELECTED
#undef Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
#undef Z_MIN_PROBE_ENDSTOP
#endif
#endif //CONDITIONALS_LCD_H

View File

@@ -28,69 +28,54 @@
#ifndef CONDITIONALS_POST_H
#define CONDITIONALS_POST_H
#if ENABLED(EMERGENCY_PARSER)
#define EMERGENCY_PARSER_CAPABILITIES " EMERGENCY_CODES:M108,M112,M410"
#else
#define EMERGENCY_PARSER_CAPABILITIES ""
#endif
/**
* Set ENDSTOPPULLUPS for unused endstop switches
*/
#if ENABLED(ENDSTOPPULLUPS)
#if ENABLED(USE_XMAX_PLUG)
#define ENDSTOPPULLUP_XMAX
#endif
#if ENABLED(USE_YMAX_PLUG)
#define ENDSTOPPULLUP_YMAX
#endif
#if ENABLED(USE_ZMAX_PLUG)
#define ENDSTOPPULLUP_ZMAX
#endif
#if ENABLED(USE_XMIN_PLUG)
#define ENDSTOPPULLUP_XMIN
#endif
#if ENABLED(USE_YMIN_PLUG)
#define ENDSTOPPULLUP_YMIN
#endif
#if ENABLED(USE_ZMIN_PLUG)
#define ENDSTOPPULLUP_ZMIN
#endif
#if DISABLED(DISABLE_Z_MIN_PROBE_ENDSTOP)
#define ENDSTOPPULLUP_ZMIN_PROBE
#endif
#endif
/**
* Axis lengths
* Axis lengths and center
*/
#define X_MAX_LENGTH (X_MAX_POS - (X_MIN_POS))
#define Y_MAX_LENGTH (Y_MAX_POS - (Y_MIN_POS))
#define Z_MAX_LENGTH (Z_MAX_POS - (Z_MIN_POS))
#define X_CENTER float((X_MIN_POS + X_MAX_POS) * 0.5)
#define Y_CENTER float((Y_MIN_POS + Y_MAX_POS) * 0.5)
#define Z_CENTER float((Z_MIN_POS + Z_MAX_POS) * 0.5)
/**
* CoreXY and CoreXZ
* CoreXY, CoreXZ, and CoreYZ - and their reverse
*/
#if ENABLED(COREXY)
#define CORE_AXIS_1 A_AXIS // XY from A + B
#define CORE_AXIS_2 B_AXIS
#define NORMAL_AXIS Z_AXIS
#elif ENABLED(COREXZ)
#define CORE_AXIS_1 A_AXIS // XZ from A + C
#define CORE_AXIS_2 C_AXIS
#define NORMAL_AXIS Y_AXIS
#elif ENABLED(COREYZ)
#define CORE_AXIS_1 B_AXIS // YZ from B + C
#define CORE_AXIS_2 C_AXIS
#define NORMAL_AXIS X_AXIS
#define CORE_IS_XY (ENABLED(COREXY) || ENABLED(COREYX))
#define CORE_IS_XZ (ENABLED(COREXZ) || ENABLED(COREZX))
#define CORE_IS_YZ (ENABLED(COREYZ) || ENABLED(COREZY))
#define IS_CORE (CORE_IS_XY || CORE_IS_XZ || CORE_IS_YZ)
#if IS_CORE
#if CORE_IS_XY
#define CORE_AXIS_1 A_AXIS
#define CORE_AXIS_2 B_AXIS
#define NORMAL_AXIS Z_AXIS
#elif CORE_IS_XZ
#define CORE_AXIS_1 A_AXIS
#define NORMAL_AXIS Y_AXIS
#define CORE_AXIS_2 C_AXIS
#elif CORE_IS_YZ
#define NORMAL_AXIS X_AXIS
#define CORE_AXIS_1 B_AXIS
#define CORE_AXIS_2 C_AXIS
#endif
#if (ENABLED(COREYX) || ENABLED(COREZX) || ENABLED(COREZY))
#define CORESIGN(n) (-(n))
#else
#define CORESIGN(n) (n)
#endif
#endif
#define IS_SCARA (ENABLED(MORGAN_SCARA) || ENABLED(MAKERARM_SCARA))
#define IS_KINEMATIC (ENABLED(DELTA) || IS_SCARA)
#define IS_CARTESIAN !IS_KINEMATIC
/**
* SCARA
* SCARA cannot use SLOWDOWN and requires QUICKHOME
*/
#if ENABLED(SCARA)
#if IS_SCARA
#undef SLOWDOWN
#define QUICK_HOME //SCARA needs Quickhome
#define QUICK_HOME
#endif
/**
@@ -106,7 +91,7 @@
#endif
#else
#if ENABLED(DELTA)
#define X_HOME_POS ((X_MAX_LENGTH) * 0.5)
#define X_HOME_POS (X_MIN_POS + (X_MAX_LENGTH) * 0.5)
#else
#define X_HOME_POS (X_HOME_DIR < 0 ? X_MIN_POS : X_MAX_POS)
#endif
@@ -122,7 +107,7 @@
#endif
#else
#if ENABLED(DELTA)
#define Y_HOME_POS ((Y_MAX_LENGTH) * 0.5)
#define Y_HOME_POS (Y_MIN_POS + (Y_MAX_LENGTH) * 0.5)
#else
#define Y_HOME_POS (Y_HOME_DIR < 0 ? Y_MIN_POS : Y_MAX_POS)
#endif
@@ -134,33 +119,10 @@
#define Z_HOME_POS (Z_HOME_DIR < 0 ? Z_MIN_POS : Z_MAX_POS)
#endif
/**
* The BLTouch Probe emulates a servo probe
*/
#if ENABLED(BLTOUCH)
#undef Z_ENDSTOP_SERVO_NR
#undef Z_SERVO_ANGLES
#define Z_ENDSTOP_SERVO_NR 0
#define Z_SERVO_ANGLES {10,90} // For BLTouch 10=deploy, 90=retract
#undef DEACTIVATE_SERVOS_AFTER_MOVE
#if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
#undef Z_MIN_ENDSTOP_INVERTING
#define Z_MIN_ENDSTOP_INVERTING false
#endif
#endif
/**
* Auto Bed Leveling and Z Probe Repeatability Test
*/
#define HAS_PROBING_PROCEDURE (ENABLED(AUTO_BED_LEVELING_FEATURE) || ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST))
// Boundaries for probing based on set limits
#define MIN_PROBE_X (max(X_MIN_POS, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
#define MAX_PROBE_X (min(X_MAX_POS, X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
#define MIN_PROBE_Y (max(Y_MIN_POS, Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
#define MAX_PROBE_Y (min(Y_MAX_POS, Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
#define HAS_Z_SERVO_ENDSTOP (defined(Z_ENDSTOP_SERVO_NR) && Z_ENDSTOP_SERVO_NR >= 0)
#define HOMING_Z_WITH_PROBE (HAS_BED_PROBE && Z_HOME_DIR < 0 && ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN))
/**
* Z Sled Probe requires Z_SAFE_HOMING
@@ -170,10 +132,11 @@
#endif
/**
* DELTA should ignore Z_SAFE_HOMING
* DELTA should ignore Z_SAFE_HOMING and SLOWDOWN
*/
#if ENABLED(DELTA)
#undef Z_SAFE_HOMING
#undef SLOWDOWN
#endif
/**
@@ -186,6 +149,11 @@
#ifndef Z_SAFE_HOMING_Y_POINT
#define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2)
#endif
#define X_TILT_FULCRUM Z_SAFE_HOMING_X_POINT
#define Y_TILT_FULCRUM Z_SAFE_HOMING_Y_POINT
#else
#define X_TILT_FULCRUM X_HOME_POS
#define Y_TILT_FULCRUM Y_HOME_POS
#endif
/**
@@ -259,8 +227,12 @@
#if TEMP_SENSOR_0 == -3
#define HEATER_0_USES_MAX6675
#define MAX6675_IS_MAX31855
#define MAX6675_TMIN -270
#define MAX6675_TMAX 1800
#elif TEMP_SENSOR_0 == -2
#define HEATER_0_USES_MAX6675
#define MAX6675_TMIN 0
#define MAX6675_TMAX 1024
#elif TEMP_SENSOR_0 == -1
#define HEATER_0_USES_AD595
#elif TEMP_SENSOR_0 == 0
@@ -343,13 +315,13 @@
/**
* ARRAY_BY_EXTRUDERS based on EXTRUDERS
*/
#define ARRAY_BY_EXTRUDERS(args...) ARRAY_N(EXTRUDERS, args)
#define ARRAY_BY_EXTRUDERS(...) ARRAY_N(EXTRUDERS, __VA_ARGS__)
#define ARRAY_BY_EXTRUDERS1(v1) ARRAY_BY_EXTRUDERS(v1, v1, v1, v1, v1, v1)
/**
* ARRAY_BY_HOTENDS based on HOTENDS
*/
#define ARRAY_BY_HOTENDS(args...) ARRAY_N(HOTENDS, args)
#define ARRAY_BY_HOTENDS(...) ARRAY_N(HOTENDS, __VA_ARGS__)
#define ARRAY_BY_HOTENDS1(v1) ARRAY_BY_HOTENDS(v1, v1, v1, v1, v1, v1)
/**
@@ -362,32 +334,89 @@
#define _XMAX_ 101
#define _YMAX_ 201
#define _ZMAX_ 301
#if Z2_USE_ENDSTOP == _XMAX_
#define Z2_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
#define Z2_MAX_PIN X_MAX_PIN
#undef USE_XMAX_PLUG
#elif Z2_USE_ENDSTOP == _YMAX_
#define Z2_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
#define Z2_MAX_PIN Y_MAX_PIN
#undef USE_YMAX_PLUG
#elif Z2_USE_ENDSTOP == _ZMAX_
#define Z2_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
#define Z2_MAX_PIN Z_MAX_PIN
#undef USE_ZMAX_PLUG
#elif Z2_USE_ENDSTOP == _XMIN_
#define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
#define Z2_MAX_PIN X_MIN_PIN
#undef USE_XMIN_PLUG
#if Z2_USE_ENDSTOP == _XMIN_
#define USE_XMIN_PLUG
#elif Z2_USE_ENDSTOP == _XMAX_
#define USE_XMAX_PLUG
#elif Z2_USE_ENDSTOP == _YMIN_
#define Z2_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
#define Z2_MAX_PIN Y_MIN_PIN
#undef USE_YMIN_PLUG
#define USE_YMIN_PLUG
#elif Z2_USE_ENDSTOP == _YMAX_
#define USE_YMAX_PLUG
#elif Z2_USE_ENDSTOP == _ZMIN_
#define Z2_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
#define Z2_MAX_PIN Z_MIN_PIN
#undef USE_ZMIN_PLUG
#define USE_ZMIN_PLUG
#elif Z2_USE_ENDSTOP == _ZMAX_
#define USE_ZMAX_PLUG
#endif
#if Z_HOME_DIR > 0
#if Z2_USE_ENDSTOP == _XMIN_
#define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
#define Z2_MAX_PIN X_MIN_PIN
#elif Z2_USE_ENDSTOP == _XMAX_
#define Z2_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
#define Z2_MAX_PIN X_MAX_PIN
#elif Z2_USE_ENDSTOP == _YMIN_
#define Z2_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
#define Z2_MAX_PIN Y_MIN_PIN
#elif Z2_USE_ENDSTOP == _YMAX_
#define Z2_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
#define Z2_MAX_PIN Y_MAX_PIN
#elif Z2_USE_ENDSTOP == _ZMIN_
#define Z2_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
#define Z2_MAX_PIN Z_MIN_PIN
#elif Z2_USE_ENDSTOP == _ZMAX_
#define Z2_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
#define Z2_MAX_PIN Z_MAX_PIN
#else
#define Z2_MAX_ENDSTOP_INVERTING false
#endif
#else
#define Z2_MAX_ENDSTOP_INVERTING false
#if Z2_USE_ENDSTOP == _XMIN_
#define Z2_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
#define Z2_MIN_PIN X_MIN_PIN
#elif Z2_USE_ENDSTOP == _XMAX_
#define Z2_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
#define Z2_MIN_PIN X_MAX_PIN
#elif Z2_USE_ENDSTOP == _YMIN_
#define Z2_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
#define Z2_MIN_PIN Y_MIN_PIN
#elif Z2_USE_ENDSTOP == _YMAX_
#define Z2_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
#define Z2_MIN_PIN Y_MAX_PIN
#elif Z2_USE_ENDSTOP == _ZMIN_
#define Z2_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
#define Z2_MIN_PIN Z_MIN_PIN
#elif Z2_USE_ENDSTOP == _ZMAX_
#define Z2_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
#define Z2_MIN_PIN Z_MAX_PIN
#else
#define Z2_MIN_ENDSTOP_INVERTING false
#endif
#endif
#endif
#define IS_Z2_OR_PROBE(P) (P == Z2_MIN_PIN || P == Z2_MAX_PIN || P == Z_MIN_PROBE_PIN)
/**
* Set ENDSTOPPULLUPS for active endstop switches
*/
#if ENABLED(ENDSTOPPULLUPS)
#if ENABLED(USE_XMAX_PLUG)
#define ENDSTOPPULLUP_XMAX
#endif
#if ENABLED(USE_YMAX_PLUG)
#define ENDSTOPPULLUP_YMAX
#endif
#if ENABLED(USE_ZMAX_PLUG)
#define ENDSTOPPULLUP_ZMAX
#endif
#if ENABLED(USE_XMIN_PLUG)
#define ENDSTOPPULLUP_XMIN
#endif
#if ENABLED(USE_YMIN_PLUG)
#define ENDSTOPPULLUP_YMIN
#endif
#if ENABLED(USE_ZMIN_PLUG)
#define ENDSTOPPULLUP_ZMIN
#endif
#endif
@@ -404,14 +433,20 @@
#define HAS_HEATER_2 (PIN_EXISTS(HEATER_2))
#define HAS_HEATER_3 (PIN_EXISTS(HEATER_3))
#define HAS_HEATER_BED (PIN_EXISTS(HEATER_BED))
#define HAS_AUTO_FAN_0 (PIN_EXISTS(EXTRUDER_0_AUTO_FAN))
#define HAS_AUTO_FAN_1 (PIN_EXISTS(EXTRUDER_1_AUTO_FAN))
#define HAS_AUTO_FAN_2 (PIN_EXISTS(EXTRUDER_2_AUTO_FAN))
#define HAS_AUTO_FAN_3 (PIN_EXISTS(EXTRUDER_3_AUTO_FAN))
#define HAS_AUTO_FAN_0 (PIN_EXISTS(E0_AUTO_FAN))
#define HAS_AUTO_FAN_1 (HOTENDS > 1 && PIN_EXISTS(E1_AUTO_FAN))
#define HAS_AUTO_FAN_2 (HOTENDS > 2 && PIN_EXISTS(E2_AUTO_FAN))
#define HAS_AUTO_FAN_3 (HOTENDS > 3 && PIN_EXISTS(E3_AUTO_FAN))
#define HAS_AUTO_FAN (HAS_AUTO_FAN_0 || HAS_AUTO_FAN_1 || HAS_AUTO_FAN_2 || HAS_AUTO_FAN_3)
#define AUTO_1_IS_0 (E1_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
#define AUTO_2_IS_0 (E2_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
#define AUTO_2_IS_1 (E2_AUTO_FAN_PIN == E1_AUTO_FAN_PIN)
#define AUTO_3_IS_0 (E3_AUTO_FAN_PIN == E0_AUTO_FAN_PIN)
#define AUTO_3_IS_1 (E3_AUTO_FAN_PIN == E1_AUTO_FAN_PIN)
#define AUTO_3_IS_2 (E3_AUTO_FAN_PIN == E2_AUTO_FAN_PIN)
#define HAS_FAN0 (PIN_EXISTS(FAN))
#define HAS_FAN1 (PIN_EXISTS(FAN1) && CONTROLLERFAN_PIN != FAN1_PIN && EXTRUDER_0_AUTO_FAN_PIN != FAN1_PIN && EXTRUDER_1_AUTO_FAN_PIN != FAN1_PIN && EXTRUDER_2_AUTO_FAN_PIN != FAN1_PIN)
#define HAS_FAN2 (PIN_EXISTS(FAN2) && CONTROLLERFAN_PIN != FAN2_PIN && EXTRUDER_0_AUTO_FAN_PIN != FAN2_PIN && EXTRUDER_1_AUTO_FAN_PIN != FAN2_PIN && EXTRUDER_2_AUTO_FAN_PIN != FAN2_PIN)
#define HAS_FAN1 (PIN_EXISTS(FAN1) && CONTROLLERFAN_PIN != FAN1_PIN && E0_AUTO_FAN_PIN != FAN1_PIN && E1_AUTO_FAN_PIN != FAN1_PIN && E2_AUTO_FAN_PIN != FAN1_PIN && E3_AUTO_FAN_PIN != FAN1_PIN)
#define HAS_FAN2 (PIN_EXISTS(FAN2) && CONTROLLERFAN_PIN != FAN2_PIN && E0_AUTO_FAN_PIN != FAN2_PIN && E1_AUTO_FAN_PIN != FAN2_PIN && E2_AUTO_FAN_PIN != FAN2_PIN && E3_AUTO_FAN_PIN != FAN2_PIN)
#define HAS_CONTROLLERFAN (PIN_EXISTS(CONTROLLERFAN))
#define HAS_SERVOS (defined(NUM_SERVOS) && NUM_SERVOS > 0)
#define HAS_SERVO_0 (PIN_EXISTS(SERVO0))
@@ -424,22 +459,25 @@
#define HAS_KILL (PIN_EXISTS(KILL))
#define HAS_SUICIDE (PIN_EXISTS(SUICIDE))
#define HAS_PHOTOGRAPH (PIN_EXISTS(PHOTOGRAPH))
#define HAS_X_MIN (PIN_EXISTS(X_MIN))
#define HAS_X_MAX (PIN_EXISTS(X_MAX))
#define HAS_Y_MIN (PIN_EXISTS(Y_MIN))
#define HAS_Y_MAX (PIN_EXISTS(Y_MAX))
#define HAS_Z_MIN (PIN_EXISTS(Z_MIN))
#define HAS_Z_MAX (PIN_EXISTS(Z_MAX))
#define HAS_X_MIN (PIN_EXISTS(X_MIN) && !IS_Z2_OR_PROBE(X_MIN_PIN))
#define HAS_X_MAX (PIN_EXISTS(X_MAX) && !IS_Z2_OR_PROBE(X_MAX_PIN))
#define HAS_Y_MIN (PIN_EXISTS(Y_MIN) && !IS_Z2_OR_PROBE(Y_MIN_PIN))
#define HAS_Y_MAX (PIN_EXISTS(Y_MAX) && !IS_Z2_OR_PROBE(Y_MAX_PIN))
#define HAS_Z_MIN (PIN_EXISTS(Z_MIN) && !IS_Z2_OR_PROBE(Z_MIN_PIN))
#define HAS_Z_MAX (PIN_EXISTS(Z_MAX) && !IS_Z2_OR_PROBE(Z_MAX_PIN))
#define HAS_Z2_MIN (PIN_EXISTS(Z2_MIN))
#define HAS_Z2_MAX (PIN_EXISTS(Z2_MAX))
#define HAS_Z_MIN_PROBE_PIN (PIN_EXISTS(Z_MIN_PROBE))
#define HAS_SOLENOID_1 (PIN_EXISTS(SOL1))
#define HAS_SOLENOID_2 (PIN_EXISTS(SOL2))
#define HAS_SOLENOID_3 (PIN_EXISTS(SOL3))
#define HAS_MICROSTEPS (PIN_EXISTS(X_MS1))
#define HAS_MICROSTEPS_X (PIN_EXISTS(X_MS1))
#define HAS_MICROSTEPS_Y (PIN_EXISTS(Y_MS1))
#define HAS_MICROSTEPS_Z (PIN_EXISTS(Z_MS1))
#define HAS_MICROSTEPS_E0 (PIN_EXISTS(E0_MS1))
#define HAS_MICROSTEPS_E1 (PIN_EXISTS(E1_MS1))
#define HAS_MICROSTEPS_E2 (PIN_EXISTS(E2_MS1))
#define HAS_MICROSTEPS (HAS_MICROSTEPS_X || HAS_MICROSTEPS_Y || HAS_MICROSTEPS_Z || HAS_MICROSTEPS_E0 || HAS_MICROSTEPS_E1 || HAS_MICROSTEPS_E2)
#define HAS_STEPPER_RESET (PIN_EXISTS(STEPPER_RESET))
#define HAS_X_ENABLE (PIN_EXISTS(X_ENABLE))
#define HAS_X2_ENABLE (PIN_EXISTS(X2_ENABLE))
@@ -476,6 +514,7 @@
#define HAS_E4_STEP (PIN_EXISTS(E4_STEP))
#define HAS_DIGIPOTSS (PIN_EXISTS(DIGIPOTSS))
#define HAS_BUZZER (PIN_EXISTS(BEEPER) || ENABLED(LCD_USE_I2C_BUZZER))
#define HAS_CASE_LIGHT (PIN_EXISTS(CASE_LIGHT))
#define HAS_MOTOR_CURRENT_PWM (PIN_EXISTS(MOTOR_CURRENT_PWM_XY) || PIN_EXISTS(MOTOR_CURRENT_PWM_Z) || PIN_EXISTS(MOTOR_CURRENT_PWM_E))
@@ -484,11 +523,11 @@
#define HAS_THERMALLY_PROTECTED_BED (HAS_TEMP_BED && HAS_HEATER_BED && ENABLED(THERMAL_PROTECTION_BED))
/**
* This value is used by M109 when trying to calculate a ballpark safe margin
* to prevent wait-forever situation.
* This setting is also used by M109 when trying to calculate
* a ballpark safe margin to prevent wait-forever situation.
*/
#ifndef EXTRUDE_MINTEMP
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MINTEMP 170
#endif
/**
@@ -548,8 +587,6 @@
#endif
#endif
#define PROBE_SELECTED (ENABLED(FIX_MOUNTED_PROBE) || ENABLED(Z_PROBE_ALLEN_KEY) || HAS_Z_SERVO_ENDSTOP || ENABLED(Z_PROBE_SLED))
#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 && PROBE_PIN_CONFIGURED)
@@ -562,6 +599,9 @@
* Bed Probe dependencies
*/
#if HAS_BED_PROBE
#if ENABLED(ENDSTOPPULLUPS) && HAS_Z_MIN_PROBE_PIN
#define ENDSTOPPULLUP_ZMIN_PROBE
#endif
#ifndef Z_PROBE_OFFSET_RANGE_MIN
#define Z_PROBE_OFFSET_RANGE_MIN -20
#endif
@@ -575,10 +615,10 @@
#define XY_PROBE_SPEED 4000
#endif
#endif
#if Z_PROBE_TRAVEL_HEIGHT > Z_PROBE_DEPLOY_HEIGHT
#define _Z_PROBE_DEPLOY_HEIGHT Z_PROBE_TRAVEL_HEIGHT
#if Z_CLEARANCE_BETWEEN_PROBES > Z_CLEARANCE_DEPLOY_PROBE
#define _Z_CLEARANCE_DEPLOY_PROBE Z_CLEARANCE_BETWEEN_PROBES
#else
#define _Z_PROBE_DEPLOY_HEIGHT Z_PROBE_DEPLOY_HEIGHT
#define _Z_CLEARANCE_DEPLOY_PROBE Z_CLEARANCE_DEPLOY_PROBE
#endif
#else
#undef X_PROBE_OFFSET_FROM_EXTRUDER
@@ -611,16 +651,21 @@
#ifndef DELTA_DIAGONAL_ROD_TRIM_TOWER_3
#define DELTA_DIAGONAL_ROD_TRIM_TOWER_3 0.0
#endif
#if ENABLED(AUTO_BED_LEVELING_GRID)
#define DELTA_BED_LEVELING_GRID
#endif
#endif
/**
* When not using other bed leveling...
* Set ABL options based on the specific type of leveling
*/
#if ENABLED(AUTO_BED_LEVELING_FEATURE) && DISABLED(AUTO_BED_LEVELING_GRID) && DISABLED(DELTA_BED_LEVELING_GRID)
#define 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 HAS_ABL (ABL_PLANAR || ABL_GRID)
#define PLANNER_LEVELING (HAS_ABL || ENABLED(MESH_BED_LEVELING))
#define HAS_PROBING_PROCEDURE (HAS_ABL || ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST))
#if HAS_PROBING_PROCEDURE
#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))
#endif
/**
@@ -633,31 +678,48 @@
#ifndef LCD_FEEDBACK_FREQUENCY_DURATION_MS
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
#endif
#elif PIN_EXISTS(BEEPER)
#else
#ifndef LCD_FEEDBACK_FREQUENCY_HZ
#define LCD_FEEDBACK_FREQUENCY_HZ 5000
#endif
#ifndef LCD_FEEDBACK_FREQUENCY_DURATION_MS
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
#endif
#else
#ifndef LCD_FEEDBACK_FREQUENCY_DURATION_MS
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
#endif
#endif
/**
* Z_HOMING_HEIGHT / Z_PROBE_TRAVEL_HEIGHT
* Z_HOMING_HEIGHT / Z_CLEARANCE_BETWEEN_PROBES
*/
#ifndef Z_HOMING_HEIGHT
#ifndef Z_PROBE_TRAVEL_HEIGHT
#ifndef Z_CLEARANCE_BETWEEN_PROBES
#define Z_HOMING_HEIGHT 0
#else
#define Z_HOMING_HEIGHT Z_PROBE_TRAVEL_HEIGHT
#define Z_HOMING_HEIGHT Z_CLEARANCE_BETWEEN_PROBES
#endif
#endif
#ifndef Z_PROBE_TRAVEL_HEIGHT
#define Z_PROBE_TRAVEL_HEIGHT Z_HOMING_HEIGHT
#ifndef Z_CLEARANCE_BETWEEN_PROBES
#define Z_CLEARANCE_BETWEEN_PROBES Z_HOMING_HEIGHT
#endif
#if IS_KINEMATIC
// Check for this in the code instead
#define MIN_PROBE_X X_MIN_POS
#define MAX_PROBE_X X_MAX_POS
#define MIN_PROBE_Y Y_MIN_POS
#define MAX_PROBE_Y Y_MAX_POS
#else
// Boundaries for probing based on set limits
#define MIN_PROBE_X (max(X_MIN_POS, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
#define MAX_PROBE_X (min(X_MAX_POS, X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
#define MIN_PROBE_Y (max(Y_MIN_POS, Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
#define MAX_PROBE_Y (min(Y_MAX_POS, Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER))
#endif
// Stepper pulse duration, in cycles
#define STEP_PULSE_CYCLES ((MINIMUM_STEPPER_PULSE) * CYCLES_PER_MICROSECOND)
#ifndef DELTA_ENDSTOP_ADJ
#define DELTA_ENDSTOP_ADJ { 0 }
#endif
#endif // CONDITIONALS_POST_H

View File

@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -133,9 +142,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -169,69 +181,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
#define POWER_SUPPLY 1
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 0
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 0
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -281,7 +310,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -328,8 +356,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
@@ -347,14 +373,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -382,9 +411,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -428,16 +461,84 @@
#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 4000, 500 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 20.0
#define DEFAULT_YJERK 20.0
#define DEFAULT_ZJERK 0.4
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -449,6 +550,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -493,9 +595,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -513,16 +612,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -531,20 +638,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 10 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -553,7 +665,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -594,7 +706,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -616,11 +728,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -645,71 +757,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -742,27 +876,6 @@
#define HOMING_FEEDRATE_XY (50*60)
#define HOMING_FEEDRATE_Z (4*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {80,80,4000,500} // default steps per unit for Ultimaker
#define DEFAULT_MAX_FEEDRATE {300, 300, 5, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {3000,3000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 20.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -932,9 +1045,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -958,7 +1071,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1270,6 +1383,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -405,6 +422,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -446,15 +466,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -483,6 +507,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -499,9 +553,20 @@
#define D_FILAMENT 2.85
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -530,7 +595,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -546,7 +622,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -563,7 +639,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -641,126 +717,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -773,27 +1059,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -33,10 +33,29 @@
# 5. Type "make upload", reset your Arduino board, and press enter to
# upload your program to the Arduino board.
#
# Note that all settings are set with ?=, this means you can override them
# from the commandline with "make HARDWARE_MOTHERBOARD=71" for example
# Note that all settings at the top of this file can be overriden from
# the command line with, for example, "make HARDWARE_MOTHERBOARD=71"
#
# To compile for RAMPS (atmega2560) with Arduino 1.6.9 at root/arduino you would use...
#
# make ARDUINO_VERSION=10609 AVR_TOOLS_PATH=/root/arduino/hardware/tools/avr/bin/ \
# HARDWARE_MOTHERBOARD=33 ARDUINO_INSTALL_DIR=/root/arduino
#
# To compile and upload simply add "upload" to the end of the line...
#
# make ARDUINO_VERSION=10609 AVR_TOOLS_PATH=/root/arduino/hardware/tools/avr/bin/ \
# HARDWARE_MOTHERBOARD=33 ARDUINO_INSTALL_DIR=/root/arduino upload
#
# If uploading doesn't work try adding the parameter "AVRDUDE_PROGRAMMER=wiring" or
# start upload manually (using stk500) like so:
#
# avrdude -C /root/arduino/hardware/tools/avr/etc/avrdude.conf -v -p m2560 -c stk500 \
# -U flash:w:applet/Marlin.hex:i -P /dev/ttyUSB0
#
# Or, try disconnecting USB to power down and then reconnecting before running avrdude.
#
# This defined the board you are compiling for (see boards.h for the options)
# This defines the board to compile for (see boards.h for your board's ID)
HARDWARE_MOTHERBOARD ?= 11
# Arduino source install directory, and version number
@@ -237,7 +256,7 @@ else
HARDWARE_DIR = ../ArduinoAddons/Arduino_0.xx
endif
endif
HARDWARE_SRC = $(HARDWARE_DIR)/marlin/avr/cores/arduino
HARDWARE_SRC= $(HARDWARE_DIR)/arduino/avr/cores/arduino
TARGET = $(notdir $(CURDIR))
@@ -251,6 +270,9 @@ VPATH += $(HARDWARE_SRC)
ifeq ($(HARDWARE_VARIANT), $(filter $(HARDWARE_VARIANT),arduino Teensy Sanguino))
VPATH += $(HARDWARE_DIR)/marlin/avr/libraries/LiquidCrystal/src
VPATH += $(HARDWARE_DIR)/marlin/avr/libraries/SPI
VPATH += $(HARDWARE_DIR)/arduino/avr/libraries/SPI
VPATH += $(HARDWARE_DIR)/arduino/avr/libraries/SPI/src
VPATH += $(ARDUINO_INSTALL_DIR)/libraries/LiquidCrystal/src
ifeq ($(LIQUID_TWI2), 1)
VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Wire
VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Wire/utility
@@ -276,6 +298,7 @@ endif
ifeq ($(HARDWARE_VARIANT), arduino)
HARDWARE_SUB_VARIANT ?= mega
VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/variants/$(HARDWARE_SUB_VARIANT)
VPATH += $(ARDUINO_INSTALL_DIR)/hardware/arduino/avr/variants/$(HARDWARE_SUB_VARIANT)
else
ifeq ($(HARDWARE_VARIANT), Sanguino)
VPATH += $(HARDWARE_DIR)/marlin/avr/variants/sanguino
@@ -297,7 +320,7 @@ CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.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 qr_solve.cpp buzzer.cpp
dac_mcp4728.cpp vector_3.cpp qr_solve.cpp endstops.cpp stopwatch.cpp utility.cpp
ifeq ($(LIQUID_TWI2), 0)
CXXSRC += LiquidCrystal.cpp
else
@@ -357,16 +380,14 @@ endif
CINCS = ${addprefix -I ,${VPATH}}
CXXINCS = ${addprefix -I ,${VPATH}}
# Compiler flag to set the C Standard level.
# c89 - "ANSI" C
# gnu89 - c89 plus GCC extensions
# c99 - ISO C99 standard (not yet fully implemented)
# gnu99 - c99 plus GCC extensions
#CSTANDARD = -std=gnu99
# Compiler flag to set the C/CPP Standard level.
CSTANDARD = -std=gnu99
CXXSTANDARD = -std=gnu++11
CDEBUG = -g$(DEBUG)
CWARN = -Wall -Wstrict-prototypes
CTUNING = -funsigned-char -funsigned-bitfields -fpack-struct \
-fshort-enums -w -ffunction-sections -fdata-sections \
-flto \
-DARDUINO=$(ARDUINO_VERSION)
ifneq ($(HARDWARE_MOTHERBOARD),)
CTUNING += -DMOTHERBOARD=${HARDWARE_MOTHERBOARD}
@@ -374,8 +395,8 @@ endif
#CEXTRA = -Wa,-adhlns=$(<:.c=.lst)
CEXTRA = -fno-use-cxa-atexit
CFLAGS := $(CDEBUG) $(CDEFS) $(CINCS) -O$(OPT) $(CWARN) $(CEXTRA) $(CTUNING)
CXXFLAGS := $(CDEFS) $(CINCS) -O$(OPT) -Wall $(CEXTRA) $(CTUNING)
CFLAGS := $(CDEBUG) $(CDEFS) $(CINCS) -O$(OPT) $(CWARN) $(CEXTRA) $(CTUNING) $(CSTANDARD)
CXXFLAGS := $(CDEFS) $(CINCS) -O$(OPT) -Wall $(CEXTRA) $(CTUNING) $(CXXSTANDARD)
#ASFLAGS = -Wa,-adhlns=$(<:.S=.lst),-gstabs
LDFLAGS = -lm
@@ -490,7 +511,7 @@ extcoff: $(TARGET).elf
# Link: create ELF output file from library.
$(BUILD_DIR)/$(TARGET).elf: $(OBJ) Configuration.h
$(Pecho) " CXX $@"
$P $(CC) $(ALL_CXXFLAGS) -Wl,--gc-sections -o $@ -L. $(OBJ) $(LDFLAGS)
$P $(CC) $(ALL_CXXFLAGS) -Wl,--gc-sections,--relax -o $@ -L. $(OBJ) $(LDFLAGS)
$(BUILD_DIR)/%.o: %.c Configuration.h Configuration_adv.h $(MAKEFILE)
$(Pecho) " CC $<"

View File

@@ -60,35 +60,36 @@
#include "stopwatch.h"
#endif
#define SERIAL_CHAR(x) MYSERIAL.write(x)
extern const char echomagic[] PROGMEM;
extern const char errormagic[] PROGMEM;
#define SERIAL_CHAR(x) (MYSERIAL.write(x))
#define SERIAL_EOL SERIAL_CHAR('\n')
#define SERIAL_PROTOCOLCHAR(x) SERIAL_CHAR(x)
#define SERIAL_PROTOCOL(x) MYSERIAL.print(x)
#define SERIAL_PROTOCOL_F(x,y) MYSERIAL.print(x,y)
#define SERIAL_PROTOCOLPGM(x) serialprintPGM(PSTR(x))
#define SERIAL_PROTOCOLLN(x) do{ MYSERIAL.print(x); SERIAL_EOL; }while(0)
#define SERIAL_PROTOCOLLNPGM(x) do{ serialprintPGM(PSTR(x "\n")); }while(0)
#define SERIAL_PROTOCOLCHAR(x) SERIAL_CHAR(x)
#define SERIAL_PROTOCOL(x) (MYSERIAL.print(x))
#define SERIAL_PROTOCOL_F(x,y) (MYSERIAL.print(x,y))
#define SERIAL_PROTOCOLPGM(x) (serialprintPGM(PSTR(x)))
#define SERIAL_PROTOCOLLN(x) do{ MYSERIAL.print(x); SERIAL_EOL; }while(0)
#define SERIAL_PROTOCOLLNPGM(x) (serialprintPGM(PSTR(x "\n")))
#define SERIAL_PROTOCOLPAIR(name, value) (serial_echopair_P(PSTR(name),(value)))
#define SERIAL_PROTOCOLLNPAIR(name, value) do{ SERIAL_PROTOCOLPAIR(name, value); SERIAL_EOL; }while(0)
#define SERIAL_PROTOCOLPAIR(name, value) SERIAL_ECHOPAIR(name, value)
#define SERIAL_ECHO_START (serialprintPGM(echomagic))
#define SERIAL_ECHO(x) SERIAL_PROTOCOL(x)
#define SERIAL_ECHOPGM(x) SERIAL_PROTOCOLPGM(x)
#define SERIAL_ECHOLN(x) SERIAL_PROTOCOLLN(x)
#define SERIAL_ECHOLNPGM(x) SERIAL_PROTOCOLLNPGM(x)
#define SERIAL_ECHOPAIR(name,value) SERIAL_PROTOCOLPAIR(name, value)
#define SERIAL_ECHOLNPAIR(name, value) SERIAL_PROTOCOLLNPAIR(name, value)
extern const char errormagic[] PROGMEM;
extern const char echomagic[] PROGMEM;
#define SERIAL_ERROR_START serialprintPGM(errormagic)
#define SERIAL_ERROR(x) SERIAL_PROTOCOL(x)
#define SERIAL_ERRORPGM(x) SERIAL_PROTOCOLPGM(x)
#define SERIAL_ERRORLN(x) SERIAL_PROTOCOLLN(x)
#define SERIAL_ERRORLNPGM(x) SERIAL_PROTOCOLLNPGM(x)
#define SERIAL_ECHO_START serialprintPGM(echomagic)
#define SERIAL_ECHO(x) SERIAL_PROTOCOL(x)
#define SERIAL_ECHOPGM(x) SERIAL_PROTOCOLPGM(x)
#define SERIAL_ECHOLN(x) SERIAL_PROTOCOLLN(x)
#define SERIAL_ECHOLNPGM(x) SERIAL_PROTOCOLLNPGM(x)
#define SERIAL_ECHOPAIR(name,value) (serial_echopair_P(PSTR(name),(value)))
#define SERIAL_ERROR_START (serialprintPGM(errormagic))
#define SERIAL_ERROR(x) SERIAL_PROTOCOL(x)
#define SERIAL_ERRORPGM(x) SERIAL_PROTOCOLPGM(x)
#define SERIAL_ERRORLN(x) SERIAL_PROTOCOLLN(x)
#define SERIAL_ERRORLNPGM(x) SERIAL_PROTOCOLLNPGM(x)
void serial_echopair_P(const char* s_P, const char *v);
void serial_echopair_P(const char* s_P, char v);
void serial_echopair_P(const char* s_P, int v);
void serial_echopair_P(const char* s_P, long v);
@@ -102,11 +103,7 @@ FORCE_INLINE void serial_echopair_P(const char* s_P, void *v) { serial_echopair_
// Things to write to serial from Program memory. Saves 400 to 2k of RAM.
FORCE_INLINE void serialprintPGM(const char* str) {
char ch;
while ((ch = pgm_read_byte(str))) {
MYSERIAL.write(ch);
str++;
}
while (char ch = pgm_read_byte(str++)) MYSERIAL.write(ch);
}
void idle(
@@ -212,6 +209,11 @@ void manage_inactivity(bool ignore_stepper_queue = false);
#endif // !MIXING_EXTRUDER
#if ENABLED(G38_PROBE_TARGET)
extern bool G38_move, // flag to tell the interrupt handler that a G38 command is being run
G38_endstop_hit; // flag from the interrupt handler to indicate if the endstop went active
#endif
/**
* The axis order in all axis related arrays is X, Y, Z, E
*/
@@ -223,7 +225,6 @@ void disable_all_steppers();
void FlushSerialRequestResend();
void ok_to_send();
void reset_bed_level();
void kill(const char*);
void quickstop_stepper();
@@ -244,8 +245,6 @@ void enqueue_and_echo_command_now(const char* cmd); // enqueue now, only return
void enqueue_and_echo_commands_P(const char* cmd); //put one or many ASCII commands at the end of the current buffer, read from flash
void clear_command_queue();
void clamp_to_software_endstops(float target[3]);
extern millis_t previous_cmd_ms;
inline void refresh_cmd_timeout() { previous_cmd_ms = millis(); }
@@ -260,27 +259,43 @@ extern int feedrate_percentage;
#define MMM_TO_MMS(MM_M) ((MM_M)/60.0)
#define MMS_TO_MMM(MM_S) ((MM_S)*60.0)
#define MMM_SCALED(MM_M) ((MM_M)*feedrate_percentage*0.01)
#define MMS_SCALED(MM_S) MMM_SCALED(MM_S)
#define MMM_TO_MMS_SCALED(MM_M) (MMS_SCALED(MMM_TO_MMS(MM_M)))
#define MMS_SCALED(MM_S) ((MM_S)*feedrate_percentage*0.01)
extern bool axis_relative_modes[];
extern bool volumetric_enabled;
extern int extruder_multiplier[EXTRUDERS]; // sets extrude multiply factor (in percent) for each extruder individually
extern int 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[3]; // axis[n].is_known
extern bool axis_homed[3]; // axis[n].is_homed
extern bool axis_known_position[XYZ]; // axis[n].is_known
extern bool axis_homed[XYZ]; // axis[n].is_homed
extern volatile bool wait_for_heatup;
extern float current_position[NUM_AXIS];
extern float position_shift[3];
extern float home_offset[3];
extern float sw_endstop_min[3];
extern float sw_endstop_max[3];
#if ENABLED(EMERGENCY_PARSER) || ENABLED(ULTIPANEL)
extern volatile bool wait_for_user;
#endif
#define LOGICAL_POSITION(POS, AXIS) (POS + home_offset[AXIS] + position_shift[AXIS])
#define RAW_POSITION(POS, AXIS) (POS - home_offset[AXIS] - position_shift[AXIS])
extern float current_position[NUM_AXIS];
extern float position_shift[XYZ];
extern float home_offset[XYZ];
#if HOTENDS > 1
extern float hotend_offset[XYZ][HOTENDS];
#endif
// Software Endstops
void update_software_endstops(AxisEnum axis);
#if ENABLED(min_software_endstops) || ENABLED(max_software_endstops)
extern bool soft_endstops_enabled;
void clamp_to_software_endstops(float target[XYZ]);
#else
#define soft_endstops_enabled false
#define clamp_to_software_endstops(x) NOOP
#endif
extern float soft_endstop_min[XYZ];
extern float soft_endstop_max[XYZ];
#define LOGICAL_POSITION(POS, AXIS) ((POS) + home_offset[AXIS] + position_shift[AXIS])
#define RAW_POSITION(POS, AXIS) ((POS) - home_offset[AXIS] - position_shift[AXIS])
#define LOGICAL_X_POSITION(POS) LOGICAL_POSITION(POS, X_AXIS)
#define LOGICAL_Y_POSITION(POS) LOGICAL_POSITION(POS, Y_AXIS)
#define LOGICAL_Z_POSITION(POS) LOGICAL_POSITION(POS, Z_AXIS)
@@ -295,26 +310,27 @@ int code_value_int();
float code_value_temp_abs();
float code_value_temp_diff();
#if IS_KINEMATIC
extern float delta[ABC];
void inverse_kinematics(const float logical[XYZ]);
#endif
#if ENABLED(DELTA)
extern float delta[3];
extern float endstop_adj[3]; // axis[n].endstop_adj
extern float delta_radius;
extern float delta_diagonal_rod;
extern float delta_segments_per_second;
extern float delta_diagonal_rod_trim_tower_1;
extern float delta_diagonal_rod_trim_tower_2;
extern float delta_diagonal_rod_trim_tower_3;
void inverse_kinematics(const float cartesian[3]);
extern float endstop_adj[ABC],
delta_radius,
delta_diagonal_rod,
delta_segments_per_second,
delta_diagonal_rod_trim_tower_1,
delta_diagonal_rod_trim_tower_2,
delta_diagonal_rod_trim_tower_3;
void recalc_delta_settings(float radius, float diagonal_rod);
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
extern int delta_grid_spacing[2];
void adjust_delta(float cartesian[3]);
#endif
#elif ENABLED(SCARA)
extern float delta[3];
extern float axis_scaling[3]; // Build size scaling
void inverse_kinematics(const float cartesian[3]);
void forward_kinematics_SCARA(float f_scara[3]);
#elif IS_SCARA
void forward_kinematics_SCARA(const float &a, const float &b);
#endif
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
extern int bilinear_grid_spacing[2];
float bilinear_z_offset(float logical[XYZ]);
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
@@ -339,12 +355,12 @@ float code_value_temp_diff();
#endif
#if ENABLED(FILAMENT_WIDTH_SENSOR)
extern float filament_width_nominal; //holds the theoretical filament diameter i.e., 3.00 or 1.75
extern bool filament_sensor; //indicates that filament sensor readings should control extrusion
extern float filament_width_meas; //holds the filament diameter as accurately measured
extern int8_t measurement_delay[]; //ring buffer to delay measurement
extern int filwidth_delay_index1, filwidth_delay_index2; //ring buffer index. used by planner, temperature, and main code
extern int meas_delay_cm; //delay distance
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
filament_width_meas; // Measured filament diameter
extern int8_t measurement_delay[]; // Ring buffer to delay measurement
extern int filwidth_delay_index[2]; // Ring buffer indexes. Used by planner, temperature, and main code
extern int meas_delay_cm; // Delay distance
#endif
#if ENABLED(FILAMENT_CHANGE_FEATURE)
@@ -382,17 +398,12 @@ extern uint8_t active_extruder;
void calculate_volumetric_multipliers();
// Buzzer
#if HAS_BUZZER && PIN_EXISTS(BEEPER)
#include "buzzer.h"
#endif
/**
* Blocking movement and shorthand functions
*/
inline void do_blocking_move_to(float x, float y, float z, float fr_mm_m=0.0);
inline void do_blocking_move_to_x(float x, float fr_mm_m=0.0);
inline void do_blocking_move_to_z(float z, float fr_mm_m=0.0);
inline void do_blocking_move_to_xy(float x, float y, float fr_mm_m=0.0);
void do_blocking_move_to(const float &x, const float &y, const float &z, const float &fr_mm_s=0.0);
void do_blocking_move_to_x(const float &x, const float &fr_mm_s=0.0);
void do_blocking_move_to_z(const float &z, const float &fr_mm_s=0.0);
void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s=0.0);
#endif //MARLIN_H

View File

@@ -67,6 +67,11 @@
#include <TMC26XStepper.h>
#endif
#if ENABLED(HAVE_TMC2130DRIVER)
#include <SPI.h>
#include <Trinamic_TMC2130.h>
#endif
#if ENABLED(HAVE_L6470DRIVER)
#include <SPI.h>
#include <L6470.h>

View File

@@ -21,18 +21,16 @@
*/
/**
MarlinSerial.cpp - Hardware serial library for Wiring
Copyright (c) 2006 Nicholas Zambetti. All right reserved.
Modified 23 November 2006 by David A. Mellis
Modified 28 September 2010 by Mark Sproul
Modified 14 February 2016 by Andreas Hardtung (added tx buffer)
*/
* MarlinSerial.cpp - Hardware serial library for Wiring
* Copyright (c) 2006 Nicholas Zambetti. All right reserved.
*
* Modified 23 November 2006 by David A. Mellis
* Modified 28 September 2010 by Mark Sproul
* Modified 14 February 2016 by Andreas Hardtung (added tx buffer)
*/
#include "MarlinSerial.h"
#include "stepper.h"
#include "Marlin.h"
#ifndef USBCON
@@ -70,8 +68,8 @@ FORCE_INLINE void store_char(unsigned char c) {
}
#if TX_BUFFER_SIZE > 0
FORCE_INLINE void _tx_udr_empty_irq(void)
{
FORCE_INLINE void _tx_udr_empty_irq(void) {
// If interrupts are enabled, there must be more data in the output
// buffer. Send the next byte
uint8_t t = tx_buffer.tail;
@@ -97,7 +95,7 @@ FORCE_INLINE void store_char(unsigned char c) {
}
#endif
#endif
#endif // TX_BUFFER_SIZE
#if defined(M_USARTx_RX_vect)
ISR(M_USARTx_RX_vect) {
@@ -162,15 +160,8 @@ void MarlinSerial::checkRx(void) {
}
int MarlinSerial::peek(void) {
int v;
CRITICAL_SECTION_START;
uint8_t t = rx_buffer.tail;
if (rx_buffer.head == t) {
v = -1;
}
else {
v = rx_buffer.buffer[t];
}
int v = rx_buffer.head == rx_buffer.tail ? -1 : rx_buffer.buffer[rx_buffer.tail];
CRITICAL_SECTION_END;
return v;
}
@@ -178,22 +169,22 @@ int MarlinSerial::peek(void) {
int MarlinSerial::read(void) {
int v;
CRITICAL_SECTION_START;
uint8_t t = rx_buffer.tail;
if (rx_buffer.head == t) {
v = -1;
}
else {
v = rx_buffer.buffer[t];
rx_buffer.tail = (uint8_t)(t + 1) & (RX_BUFFER_SIZE - 1);
}
uint8_t t = rx_buffer.tail;
if (rx_buffer.head == t) {
v = -1;
}
else {
v = rx_buffer.buffer[t];
rx_buffer.tail = (uint8_t)(t + 1) & (RX_BUFFER_SIZE - 1);
}
CRITICAL_SECTION_END;
return v;
}
uint8_t MarlinSerial::available(void) {
CRITICAL_SECTION_START;
uint8_t h = rx_buffer.head;
uint8_t t = rx_buffer.tail;
uint8_t h = rx_buffer.head,
t = rx_buffer.tail;
CRITICAL_SECTION_END;
return (uint8_t)(RX_BUFFER_SIZE + h - t) & (RX_BUFFER_SIZE - 1);
}
@@ -388,23 +379,18 @@ void MarlinSerial::println(double n, int digits) {
// Private Methods /////////////////////////////////////////////////////////////
void MarlinSerial::printNumber(unsigned long n, uint8_t base) {
unsigned char buf[8 * sizeof(long)]; // Assumes 8-bit chars.
unsigned long i = 0;
if (n == 0) {
if (n) {
unsigned char buf[8 * sizeof(long)]; // Enough space for base 2
int8_t i = 0;
while (n) {
buf[i++] = n % base;
n /= base;
}
while (i--)
print((char)(buf[i] + (buf[i] < 10 ? '0' : 'A' - 10)));
}
else
print('0');
return;
}
while (n > 0) {
buf[i++] = n % base;
n /= base;
}
for (; i > 0; i--)
print((char)(buf[i - 1] < 10 ?
'0' + buf[i - 1] :
'A' + buf[i - 1] - 10));
}
void MarlinSerial::printFloat(double number, uint8_t digits) {
@@ -417,7 +403,7 @@ void MarlinSerial::printFloat(double number, uint8_t digits) {
// Round correctly so that print(1.999, 2) prints as "2.00"
double rounding = 0.5;
for (uint8_t i = 0; i < digits; ++i)
rounding /= 10.0;
rounding *= 0.1;
number += rounding;
@@ -427,14 +413,15 @@ void MarlinSerial::printFloat(double number, uint8_t digits) {
print(int_part);
// Print the decimal point, but only if there are digits beyond
if (digits > 0) print('.');
// Extract digits from the remainder one at a time
while (digits-- > 0) {
remainder *= 10.0;
int toPrint = int(remainder);
print(toPrint);
remainder -= toPrint;
if (digits) {
print('.');
// Extract digits from the remainder one at a time
while (digits--) {
remainder *= 10.0;
int toPrint = int(remainder);
print(toPrint);
remainder -= toPrint;
}
}
}
// Preinstantiate Objects //////////////////////////////////////////////////////
@@ -521,7 +508,7 @@ MarlinSerial customizedSerial;
if (c == '\n') {
switch (state) {
case state_M108:
wait_for_heatup = false;
wait_for_user = wait_for_heatup = false;
break;
case state_M112:
kill(PSTR(MSG_KILLED));
@@ -536,4 +523,5 @@ MarlinSerial customizedSerial;
}
}
}
#endif

View File

@@ -127,47 +127,47 @@ class MarlinSerial { //: public Stream
public:
MarlinSerial();
void begin(long);
void end();
int peek(void);
int read(void);
void flush(void);
uint8_t available(void);
void checkRx(void);
void write(uint8_t c);
static void begin(long);
static void end();
static int peek(void);
static int read(void);
static void flush(void);
static uint8_t available(void);
static void checkRx(void);
static void write(uint8_t c);
#if TX_BUFFER_SIZE > 0
uint8_t availableForWrite(void);
void flushTX(void);
static uint8_t availableForWrite(void);
static void flushTX(void);
#endif
private:
void printNumber(unsigned long, uint8_t);
void printFloat(double, uint8_t);
static void printNumber(unsigned long, uint8_t);
static void printFloat(double, uint8_t);
public:
FORCE_INLINE void write(const char* str) { while (*str) write(*str++); }
FORCE_INLINE void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
FORCE_INLINE void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
FORCE_INLINE void print(const char* str) { write(str); }
static FORCE_INLINE 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++); }
static FORCE_INLINE 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); }
void print(char, int = BYTE);
void print(unsigned char, int = BYTE);
void print(int, int = DEC);
void print(unsigned int, int = DEC);
void print(long, int = DEC);
void print(unsigned long, int = DEC);
void print(double, int = 2);
static void print(char, int = BYTE);
static void print(unsigned char, int = BYTE);
static void print(int, int = DEC);
static void print(unsigned int, int = DEC);
static void print(long, int = DEC);
static void print(unsigned long, int = DEC);
static void print(double, int = 2);
void println(const String& s);
void println(const char[]);
void println(char, int = BYTE);
void println(unsigned char, int = BYTE);
void println(int, int = DEC);
void println(unsigned int, int = DEC);
void println(long, int = DEC);
void println(unsigned long, int = DEC);
void println(double, int = 2);
void println(void);
static void println(const String& s);
static void println(const char[]);
static void println(char, int = BYTE);
static void println(unsigned char, int = BYTE);
static void println(int, int = DEC);
static void println(unsigned int, int = DEC);
static void println(long, int = DEC);
static void println(unsigned long, int = DEC);
static void println(double, int = 2);
static void println(void);
};
extern MarlinSerial customizedSerial;

6454
Marlin/Marlin_main.cpp Normal file → Executable file

File diff suppressed because it is too large Load Diff

View File

@@ -30,8 +30,8 @@
* Due to the high number of issues related with old versions of Arduino IDE
* we now prevent Marlin from compiling with older toolkits.
*/
#if !defined(ARDUINO) || ARDUINO < 10600
#error "Versions of Arduino IDE prior to 1.6.0 are no longer supported, please update your toolkit."
#if !defined(ARDUINO) || ARDUINO < 10608
#error "Versions of Arduino IDE prior to 1.6.8 are no longer supported, please update your toolkit."
#endif
/**
@@ -48,6 +48,115 @@
#error "You are using an old Configuration_adv.h file, update it before building Marlin."
#endif
/**
* Warnings for old configurations
*/
#if WATCH_TEMP_PERIOD > 500
#error "WATCH_TEMP_PERIOD now uses seconds instead of milliseconds."
#elif DISABLED(THERMAL_PROTECTION_HOTENDS) && (defined(WATCH_TEMP_PERIOD) || defined(THERMAL_PROTECTION_PERIOD))
#error "Thermal Runaway Protection for hotends is now enabled with THERMAL_PROTECTION_HOTENDS."
#elif DISABLED(THERMAL_PROTECTION_BED) && defined(THERMAL_PROTECTION_BED_PERIOD)
#error "Thermal Runaway Protection for the bed is now enabled with THERMAL_PROTECTION_BED."
#elif (CORE_IS_XZ || CORE_IS_YZ) && ENABLED(Z_LATE_ENABLE)
#error "Z_LATE_ENABLE can't be used with COREXZ, COREZX, COREYZ, or COREZY."
#elif defined(X_HOME_RETRACT_MM)
#error "[XYZ]_HOME_RETRACT_MM settings have been renamed [XYZ]_HOME_BUMP_MM."
#elif defined(SDCARDDETECTINVERTED)
#error "SDCARDDETECTINVERTED is now SD_DETECT_INVERTED. Please update your configuration."
#elif defined(BTENABLED)
#error "BTENABLED is now BLUETOOTH. Please update your configuration."
#elif defined(CUSTOM_MENDEL_NAME)
#error "CUSTOM_MENDEL_NAME is now CUSTOM_MACHINE_NAME. Please update your configuration."
#elif defined(HAS_AUTOMATIC_VERSIONING)
#error "HAS_AUTOMATIC_VERSIONING is now USE_AUTOMATIC_VERSIONING. Please update your configuration."
#elif defined(SDSLOW)
#error "SDSLOW deprecated. Set SPI_SPEED to SPI_HALF_SPEED instead."
#elif defined(SDEXTRASLOW)
#error "SDEXTRASLOW deprecated. Set SPI_SPEED to SPI_QUARTER_SPEED instead."
#elif defined(FILAMENT_SENSOR)
#error "FILAMENT_SENSOR is deprecated. Use FILAMENT_WIDTH_SENSOR instead."
#elif defined(DISABLE_MAX_ENDSTOPS) || defined(DISABLE_MIN_ENDSTOPS)
#error "DISABLE_MAX_ENDSTOPS and DISABLE_MIN_ENDSTOPS deprecated. Use individual USE_*_PLUG options instead."
#elif ENABLED(Z_DUAL_ENDSTOPS) && !defined(Z2_USE_ENDSTOP)
#error "Z_DUAL_ENDSTOPS settings are simplified. Just set Z2_USE_ENDSTOP to the endstop you want to repurpose for Z2"
#elif defined(LANGUAGE_INCLUDE)
#error "LANGUAGE_INCLUDE has been replaced by LCD_LANGUAGE. Please update your configuration."
#elif defined(EXTRUDER_OFFSET_X) || defined(EXTRUDER_OFFSET_Y)
#error "EXTRUDER_OFFSET_[XY] is deprecated. Use HOTEND_OFFSET_[XY] instead."
#elif defined(PID_PARAMS_PER_EXTRUDER)
#error "PID_PARAMS_PER_EXTRUDER is deprecated. Use PID_PARAMS_PER_HOTEND instead."
#elif defined(EXTRUDER_WATTS) || defined(BED_WATTS)
#error "EXTRUDER_WATTS and BED_WATTS are deprecated. Remove them from your configuration."
#elif defined(SERVO_ENDSTOP_ANGLES)
#error "SERVO_ENDSTOP_ANGLES is deprecated. Use Z_SERVO_ANGLES instead."
#elif defined(X_ENDSTOP_SERVO_NR) || defined(Y_ENDSTOP_SERVO_NR)
#error "X_ENDSTOP_SERVO_NR and Y_ENDSTOP_SERVO_NR are deprecated and should be removed."
#elif defined(DEFAULT_XYJERK)
#error "DEFAULT_XYJERK is deprecated. Use DEFAULT_XJERK and DEFAULT_YJERK instead."
#elif defined(XY_TRAVEL_SPEED)
#error "XY_TRAVEL_SPEED is deprecated. Use XY_PROBE_SPEED instead."
#elif defined(PROBE_SERVO_DEACTIVATION_DELAY)
#error "PROBE_SERVO_DEACTIVATION_DELAY is deprecated. Use DEACTIVATE_SERVOS_AFTER_MOVE instead."
#elif defined(SERVO_DEACTIVATION_DELAY)
#error "SERVO_DEACTIVATION_DELAY is deprecated. Use SERVO_DELAY instead."
#elif ENABLED(FILAMENTCHANGEENABLE)
#error "FILAMENTCHANGEENABLE is now FILAMENT_CHANGE_FEATURE. Please update your configuration."
#elif defined(PLA_PREHEAT_HOTEND_TEMP)
#error "PLA_PREHEAT_HOTEND_TEMP is now PREHEAT_1_TEMP_HOTEND. Please update your configuration."
#elif defined(PLA_PREHEAT_HPB_TEMP)
#error "PLA_PREHEAT_HPB_TEMP is now PREHEAT_1_TEMP_BED. Please update your configuration."
#elif defined(PLA_PREHEAT_FAN_SPEED)
#error "PLA_PREHEAT_FAN_SPEED is now PREHEAT_1_FAN_SPEED. Please update your configuration."
#elif defined(ABS_PREHEAT_HOTEND_TEMP)
#error "ABS_PREHEAT_HOTEND_TEMP is now PREHEAT_2_TEMP_HOTEND. Please update your configuration."
#elif defined(ABS_PREHEAT_HPB_TEMP)
#error "ABS_PREHEAT_HPB_TEMP is now PREHEAT_2_TEMP_BED. Please update your configuration."
#elif defined(ABS_PREHEAT_FAN_SPEED)
#error "ABS_PREHEAT_FAN_SPEED is now PREHEAT_2_FAN_SPEED. Please update your configuration."
#elif defined(ENDSTOPS_ONLY_FOR_HOMING)
#error "ENDSTOPS_ONLY_FOR_HOMING is deprecated. Use (disable) ENDSTOPS_ALWAYS_ON_DEFAULT instead."
#elif defined(HOMING_FEEDRATE)
#error "HOMING_FEEDRATE is deprecated. Set individual rates with HOMING_FEEDRATE_(XY|Z|E) instead."
#elif defined(MANUAL_HOME_POSITIONS)
#error "MANUAL_HOME_POSITIONS is deprecated. Set MANUAL_[XYZ]_HOME_POS as-needed instead."
#elif defined(PID_ADD_EXTRUSION_RATE)
#error "PID_ADD_EXTRUSION_RATE is now PID_EXTRUSION_SCALING and is DISABLED by default. Are you sure you want to use this option? Please update your configuration."
#elif defined(Z_RAISE_BEFORE_HOMING)
#error "Z_RAISE_BEFORE_HOMING is now Z_HOMING_HEIGHT. Please update your configuration."
#elif defined(MIN_Z_HEIGHT_FOR_HOMING)
#error "MIN_Z_HEIGHT_FOR_HOMING is now Z_HOMING_HEIGHT. Please update your configuration."
#elif defined(Z_RAISE_BEFORE_PROBING) || defined(Z_RAISE_AFTER_PROBING)
#error "Z_RAISE_(BEFORE|AFTER)_PROBING are deprecated. Use Z_CLEARANCE_DEPLOY_PROBE instead."
#elif defined(Z_RAISE_PROBE_DEPLOY_STOW) || defined(Z_RAISE_BETWEEN_PROBINGS)
#error "Z_RAISE_PROBE_DEPLOY_STOW and Z_RAISE_BETWEEN_PROBINGS are now Z_CLEARANCE_DEPLOY_PROBE and Z_CLEARANCE_BETWEEN_PROBES. Please update your configuration."
#elif defined(Z_PROBE_DEPLOY_HEIGHT) || defined(Z_PROBE_TRAVEL_HEIGHT)
#error "Z_PROBE_DEPLOY_HEIGHT and Z_PROBE_TRAVEL_HEIGHT are now Z_CLEARANCE_DEPLOY_PROBE and Z_CLEARANCE_BETWEEN_PROBES. Please update your configuration."
#elif !defined(MIN_STEPS_PER_SEGMENT)
#error Please replace "const int dropsegments" with "#define MIN_STEPS_PER_SEGMENT" (and increase by 1) in Configuration_adv.h.
#elif defined(PREVENT_DANGEROUS_EXTRUDE)
#error "PREVENT_DANGEROUS_EXTRUDE is now PREVENT_COLD_EXTRUSION. Please update your configuration."
#elif defined(SCARA)
#error "SCARA is now MORGAN_SCARA. Please update your configuration."
#elif defined(ENABLE_AUTO_BED_LEVELING)
#error "ENABLE_AUTO_BED_LEVELING is deprecated. Specify AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_3POINT."
#elif defined(AUTO_BED_LEVELING_FEATURE)
#error "AUTO_BED_LEVELING_FEATURE is deprecated. Specify AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_BILINEAR, or AUTO_BED_LEVELING_3POINT."
#elif defined(ABL_GRID_POINTS)
#error "ABL_GRID_POINTS is now ABL_GRID_POINTS_X and ABL_GRID_POINTS_Y. Please update your configuration."
#elif defined(BEEPER)
#error "BEEPER is now BEEPER_PIN. Please update your pins definitions."
#elif defined(SDCARDDETECT)
#error "SDCARDDETECT is now SD_DETECT_PIN. Please update your pins definitions."
#elif defined(STAT_LED_RED) || defined(STAT_LED_BLUE)
#error "STAT_LED_RED/STAT_LED_BLUE are now STAT_LED_RED_PIN/STAT_LED_BLUE_PIN. Please update your pins definitions."
#elif defined(LCD_PIN_BL)
#error "LCD_PIN_BL is now LCD_BACKLIGHT_PIN. Please update your pins definitions."
#elif defined(LCD_PIN_RESET)
#error "LCD_PIN_RESET is now LCD_RESET_PIN. Please update your pins definitions."
#elif defined(EXTRUDER_0_AUTO_FAN_PIN) || defined(EXTRUDER_1_AUTO_FAN_PIN) || defined(EXTRUDER_2_AUTO_FAN_PIN) || defined(EXTRUDER_3_AUTO_FAN_PIN)
#error "EXTRUDER_[0123]_AUTO_FAN_PIN is now E[0123]_AUTO_FAN_PIN. Please update your Configuration_adv.h."
#endif
/**
* Marlin release, version and default string
*/
@@ -88,15 +197,29 @@
#if ENABLED(LCD_PROGRESS_BAR)
#if DISABLED(SDSUPPORT)
#error "LCD_PROGRESS_BAR requires SDSUPPORT."
#endif
#if ENABLED(DOGLCD)
#elif ENABLED(DOGLCD)
#error "LCD_PROGRESS_BAR does not apply to graphical displays."
#endif
#if 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."
#endif
#endif
/**
* Delta requirements
*/
#if ENABLED(DELTA)
#if DISABLED(USE_XMAX_PLUG) && DISABLED(USE_YMAX_PLUG) && DISABLED(USE_ZMAX_PLUG)
#error "You probably want to use Max Endstops for DELTA!"
#endif
#if ABL_GRID
#if (ABL_GRID_POINTS_X & 1) == 0 || (ABL_GRID_POINTS_Y & 1) == 0
#error "DELTA requires ABL_GRID_POINTS_X and ABL_GRID_POINTS_Y to be odd numbers."
#elif ABL_GRID_POINTS_X < 3
#error "DELTA requires ABL_GRID_POINTS_X and ABL_GRID_POINTS_Y to be 3 or higher."
#endif
#endif
#endif
/**
* Babystepping
*/
@@ -197,12 +320,8 @@
/**
* Limited number of servos
*/
#if defined(NUM_SERVOS) && NUM_SERVOS > 0
#if NUM_SERVOS > 4
#error "The maximum number of SERVOS in Marlin is 4."
#elif HAS_Z_SERVO_ENDSTOP && Z_ENDSTOP_SERVO_NR >= NUM_SERVOS
#error "Z_ENDSTOP_SERVO_NR must be smaller than NUM_SERVOS."
#endif
#if NUM_SERVOS > 4
#error "The maximum number of SERVOS in Marlin is 4."
#endif
/**
@@ -226,27 +345,90 @@
#error "To use BED_LIMIT_SWITCHING you must disable PIDTEMPBED."
#endif
/**
* Allow only one bed leveling option to be defined
*/
#if HAS_ABL
#define COUNT_LEV_1 0
#if ENABLED(AUTO_BED_LEVELING_LINEAR)
#define COUNT_LEV_2 INCREMENT(COUNT_LEV_1)
#else
#define COUNT_LEV_2 COUNT_LEV_1
#endif
#if ENABLED(AUTO_BED_LEVELING_3POINT)
#define COUNT_LEV_3 INCREMENT(COUNT_LEV_2)
#else
#define COUNT_LEV_3 COUNT_LEV_2
#endif
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
#define COUNT_LEV_4 INCREMENT(COUNT_LEV_3)
#else
#define COUNT_LEV_4 COUNT_LEV_3
#endif
#if ENABLED(MESH_BED_LEVELING)
#define COUNT_LEV_5 INCREMENT(COUNT_LEV_4)
#else
#define COUNT_LEV_5 COUNT_LEV_4
#endif
#if COUNT_LEV_5 > 1
#error "Select only one of: MESH_BED_LEVELING, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT, or AUTO_BED_LEVELING_BILINEAR."
#endif
#endif
/**
* Mesh Bed Leveling
*/
#if ENABLED(MESH_BED_LEVELING)
#if ENABLED(DELTA)
#error "MESH_BED_LEVELING does not yet support DELTA printers."
#elif ENABLED(AUTO_BED_LEVELING_FEATURE)
#error "Select AUTO_BED_LEVELING_FEATURE or MESH_BED_LEVELING, not both."
#elif MESH_NUM_X_POINTS > 9 || MESH_NUM_Y_POINTS > 9
#error "MESH_NUM_X_POINTS and MESH_NUM_Y_POINTS must be less than 10."
#endif
#elif ENABLED(MANUAL_BED_LEVELING)
#error "MESH_BED_LEVELING is required for MANUAL_BED_LEVELING."
#error "MANUAL_BED_LEVELING only applies to MESH_BED_LEVELING."
#endif
/**
* Probes
*/
#if PROBE_SELECTED
/**
* Allow only one probe option to be defined
*/
#define COUNT_PROBE_1 0
#if ENABLED(FIX_MOUNTED_PROBE)
#define COUNT_PROBE_2 INCREMENT(COUNT_PROBE_1)
#else
#define COUNT_PROBE_2 COUNT_PROBE_1
#endif
#if HAS_Z_SERVO_ENDSTOP && DISABLED(BLTOUCH)
#define COUNT_PROBE_3 INCREMENT(COUNT_PROBE_2)
#else
#define COUNT_PROBE_3 COUNT_PROBE_2
#endif
#if ENABLED(BLTOUCH)
#define COUNT_PROBE_4 INCREMENT(COUNT_PROBE_3)
#else
#define COUNT_PROBE_4 COUNT_PROBE_3
#endif
#if ENABLED(Z_PROBE_ALLEN_KEY)
#define COUNT_PROBE_5 INCREMENT(COUNT_PROBE_4)
#else
#define COUNT_PROBE_5 COUNT_PROBE_4
#endif
#if ENABLED(Z_PROBE_SLED)
#define COUNT_PROBE_6 INCREMENT(COUNT_PROBE_5)
#else
#define COUNT_PROBE_6 COUNT_PROBE_5
#endif
#if COUNT_PROBE_6 > 1
#error "Please enable only one probe: FIX_MOUNTED_PROBE, Z Servo, BLTOUCH, Z_PROBE_ALLEN_KEY, or Z_PROBE_SLED."
#endif
/**
* Z_PROBE_SLED is incompatible with DELTA
*/
#if ENABLED(Z_PROBE_SLED) && ENABLED(DELTA)
#error "You cannot use Z_PROBE_SLED with DELTA."
#endif
@@ -258,90 +440,40 @@
#ifndef NUM_SERVOS
#error "You must set NUM_SERVOS for a Z servo probe (Z_ENDSTOP_SERVO_NR)."
#elif Z_ENDSTOP_SERVO_NR >= NUM_SERVOS
#error "Z_ENDSTOP_SERVO_NR must be less than NUM_SERVOS."
#error "Z_ENDSTOP_SERVO_NR must be smaller than NUM_SERVOS."
#endif
#endif
/**
* A probe needs a pin
* Require pin options and pins to be defined
*/
#if !PROBE_PIN_CONFIGURED
#error "A probe needs a pin! Use Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN or Z_MIN_PROBE_PIN."
#endif
/**
* Require a Z min pin
*/
#if HAS_Z_MIN
// Z_MIN_PIN and Z_MIN_PROBE_PIN can't co-exist when Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
#if HAS_Z_MIN_PROBE_PIN && ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
#error "A probe cannot have more than one pin! Use Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN or Z_MIN_PROBE_PIN."
#if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
#error "Enable only one option: Z_MIN_PROBE_ENDSTOP or Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN."
#elif DISABLED(USE_ZMIN_PLUG)
#error "Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN requires USE_ZMIN_PLUG to be enabled."
#elif !HAS_Z_MIN
#error "Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN requires the Z_MIN_PIN to be defined."
#endif
#elif !HAS_Z_MIN_PROBE_PIN || (DISABLED(Z_MIN_PROBE_ENDSTOP) || ENABLED(DISABLE_Z_MIN_PROBE_ENDSTOP))
// A pin was set for the Z probe, but not enabled.
#error "A probe requires a Z_MIN or Z_PROBE pin. Z_MIN_PIN or Z_MIN_PROBE_PIN must point to a valid hardware pin."
#endif
/**
* Make sure the plug is enabled if it's used
*/
#if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) && DISABLED(USE_ZMIN_PLUG)
#error "You must enable USE_ZMIN_PLUG if any probe or endstop is connected to the ZMIN plug."
#endif
/**
* Only allow one probe option to be defined
*/
#if (ENABLED(FIX_MOUNTED_PROBE) && (ENABLED(Z_PROBE_ALLEN_KEY) || HAS_Z_SERVO_ENDSTOP || ENABLED(Z_PROBE_SLED))) \
|| (ENABLED(Z_PROBE_ALLEN_KEY) && (HAS_Z_SERVO_ENDSTOP || ENABLED(Z_PROBE_SLED))) \
|| (HAS_Z_SERVO_ENDSTOP && ENABLED(Z_PROBE_SLED))
#error "Please define only one type of probe: Z Servo, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or FIX_MOUNTED_PROBE."
#endif
/**
* Don't allow nonsense probe-pin settings
*/
#if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) && ENABLED(Z_MIN_PROBE_ENDSTOP)
#error "You can't enable both Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN and Z_MIN_PROBE_ENDSTOP."
#elif ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) && ENABLED(DISABLE_Z_MIN_PROBE_ENDSTOP)
#error "Don't enable DISABLE_Z_MIN_PROBE_ENDSTOP with Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN."
#elif ENABLED(DISABLE_Z_MIN_PROBE_ENDSTOP) && DISABLED(Z_MIN_PROBE_ENDSTOP)
#error "DISABLE_Z_MIN_PROBE_ENDSTOP requires Z_MIN_PROBE_ENDSTOP to be set."
#endif
/**
* Require a Z probe pin if Z_MIN_PROBE_ENDSTOP is enabled.
*/
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
#elif ENABLED(Z_MIN_PROBE_ENDSTOP)
#if !HAS_Z_MIN_PROBE_PIN
#error "Z_MIN_PROBE_ENDSTOP requires a Z_MIN_PROBE_PIN in your board's pins_XXXX.h file."
#error "Z_MIN_PROBE_ENDSTOP requires the Z_MIN_PROBE_PIN to be defined."
#endif
// Forcing Servo definitions can break some hall effect sensor setups. Leaving these here for further comment.
//#ifndef NUM_SERVOS
// #error "You must have NUM_SERVOS defined and there must be at least 1 configured to use Z_MIN_PROBE_ENDSTOP."
//#endif
//#if defined(NUM_SERVOS) && NUM_SERVOS < 1
// #error "You must have at least 1 servo defined for NUM_SERVOS to use Z_MIN_PROBE_ENDSTOP."
//#endif
//#if Z_ENDSTOP_SERVO_NR < 0
// #error "You must have Z_ENDSTOP_SERVO_NR set to at least 0 or above to use Z_MIN_PROBE_ENDSTOP."
//#endif
//#ifndef Z_SERVO_ANGLES
// #error "You must have Z_SERVO_ANGLES defined for Z Extend and Retract to use Z_MIN_PROBE_ENDSTOP."
//#endif
#else
#error "You must enable either Z_MIN_PROBE_ENDSTOP or Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use a probe."
#endif
/**
* Make sure Z raise values are set
*/
#if !defined(Z_PROBE_DEPLOY_HEIGHT)
#error "You must set Z_PROBE_DEPLOY_HEIGHT in your configuration."
#elif !defined(Z_PROBE_TRAVEL_HEIGHT)
#error "You must set Z_PROBE_TRAVEL_HEIGHT in your configuration."
#elif Z_PROBE_DEPLOY_HEIGHT < 0
#error "Probes need Z_PROBE_DEPLOY_HEIGHT >= 0."
#elif Z_PROBE_TRAVEL_HEIGHT < 0
#error "Probes need Z_PROBE_TRAVEL_HEIGHT >= 0."
#if !defined(Z_CLEARANCE_DEPLOY_PROBE)
#error "You must define Z_CLEARANCE_DEPLOY_PROBE in your configuration."
#elif !defined(Z_CLEARANCE_BETWEEN_PROBES)
#error "You must define Z_CLEARANCE_BETWEEN_PROBES in your configuration."
#elif Z_CLEARANCE_DEPLOY_PROBE < 0
#error "Probes need Z_CLEARANCE_DEPLOY_PROBE >= 0."
#elif Z_CLEARANCE_BETWEEN_PROBES < 0
#error "Probes need Z_CLEARANCE_BETWEEN_PROBES >= 0."
#endif
#else
@@ -349,14 +481,21 @@
/**
* Require some kind of probe for bed leveling and probe testing
*/
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#error "AUTO_BED_LEVELING_FEATURE requires a probe! Define a Z Servo, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or FIX_MOUNTED_PROBE."
#if HAS_ABL
#error "Auto Bed Leveling requires a probe! Define a Z Servo, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or FIX_MOUNTED_PROBE."
#elif ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST)
#error "Z_MIN_PROBE_REPEATABILITY_TEST requires a probe! Define a Z Servo, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or FIX_MOUNTED_PROBE."
#endif
#endif
/**
* Homing Bump
*/
#if X_HOME_BUMP_MM < 0 || Y_HOME_BUMP_MM < 0 || Z_HOME_BUMP_MM < 0
#error "[XYZ]_HOME_BUMP_MM must be greater than or equal to 0."
#endif
/**
* Make sure Z_SAFE_HOMING point is reachable
*/
@@ -379,19 +518,27 @@
/**
* Auto Bed Leveling
*/
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if HAS_ABL
#if ENABLED(USE_RAW_KINEMATICS)
#error "USE_RAW_KINEMATICS is not compatible with AUTO_BED_LEVELING"
#endif
/**
* Delta has limited bed leveling options
* Delta and SCARA have limited bed leveling options
*/
#if ENABLED(DELTA) && DISABLED(AUTO_BED_LEVELING_GRID)
#error "You must use AUTO_BED_LEVELING_GRID for DELTA bed leveling."
#if DISABLED(AUTO_BED_LEVELING_BILINEAR)
#if ENABLED(DELTA)
#error "Only AUTO_BED_LEVELING_BILINEAR is supported for DELTA bed leveling."
#elif ENABLED(SCARA)
#error "Only AUTO_BED_LEVELING_BILINEAR is supported for SCARA bed leveling."
#endif
#endif
/**
* Check if Probe_Offset * Grid Points is greater than Probing Range
*/
#if ENABLED(AUTO_BED_LEVELING_GRID)
#if ABL_GRID
#ifndef DELTA_PROBEABLE_RADIUS
// Be sure points are in the right order
#if LEFT_PROBE_BED_POSITION > RIGHT_PROBE_BED_POSITION
@@ -410,7 +557,7 @@
#error "The given BACK_PROBE_BED_POSITION can't be reached by the Z probe."
#endif
#endif
#else // !AUTO_BED_LEVELING_GRID
#else // !ABL_GRID
// Check the triangulation points
#if ABL_PROBE_PT_1_X < MIN_PROBE_X || ABL_PROBE_PT_1_X > MAX_PROBE_X
@@ -427,9 +574,9 @@
#error "The given ABL_PROBE_PT_3_Y can't be reached by the Z probe."
#endif
#endif // !AUTO_BED_LEVELING_GRID
#endif // !ABL_GRID
#endif // AUTO_BED_LEVELING_FEATURE
#endif // HAS_ABL
/**
* Advance Extrusion
@@ -466,11 +613,54 @@
/**
* Don't set more than one kinematic type
*/
#if (ENABLED(DELTA) && (ENABLED(SCARA) || ENABLED(COREXY) || ENABLED(COREXZ) || ENABLED(COREYZ))) \
|| (ENABLED(SCARA) && (ENABLED(COREXY) || ENABLED(COREXZ) || ENABLED(COREYZ))) \
|| (ENABLED(COREXY) && (ENABLED(COREXZ) || ENABLED(COREYZ))) \
|| (ENABLED(COREXZ) && ENABLED(COREYZ))
#error "Please enable only one of DELTA, SCARA, COREXY, COREXZ, or COREYZ."
#define COUNT_KIN_1 0
#if ENABLED(DELTA)
#define COUNT_KIN_2 INCREMENT(COUNT_KIN_1)
#else
#define COUNT_KIN_2 COUNT_KIN_1
#endif
#if ENABLED(MORGAN_SCARA)
#define COUNT_KIN_3 INCREMENT(COUNT_KIN_2)
#else
#define COUNT_KIN_3 COUNT_KIN_2
#endif
#if ENABLED(MAKERARM_SCARA)
#define COUNT_KIN_4 INCREMENT(COUNT_KIN_3)
#else
#define COUNT_KIN_4 COUNT_KIN_3
#endif
#if ENABLED(COREXY)
#define COUNT_KIN_5 INCREMENT(COUNT_KIN_4)
#else
#define COUNT_KIN_5 COUNT_KIN_4
#endif
#if ENABLED(COREXZ)
#define COUNT_KIN_6 INCREMENT(COUNT_KIN_5)
#else
#define COUNT_KIN_6 COUNT_KIN_5
#endif
#if ENABLED(COREYZ)
#define COUNT_KIN_7 INCREMENT(COUNT_KIN_6)
#else
#define COUNT_KIN_7 COUNT_KIN_6
#endif
#if ENABLED(COREYX)
#define COUNT_KIN_8 INCREMENT(COUNT_KIN_7)
#else
#define COUNT_KIN_8 COUNT_KIN_7
#endif
#if ENABLED(COREZX)
#define COUNT_KIN_9 INCREMENT(COUNT_KIN_8)
#else
#define COUNT_KIN_9 COUNT_KIN_8
#endif
#if ENABLED(COREZY)
#define COUNT_KIN_10 INCREMENT(COUNT_KIN_9)
#else
#define COUNT_KIN_10 COUNT_KIN_9
#endif
#if COUNT_KIN_10 > 1
#error "Please enable only one of DELTA, MORGAN_SCARA, MAKERARM_SCARA, COREXY, COREYX, COREXZ, COREZX, COREYZ, or COREZY."
#endif
/**
@@ -487,8 +677,8 @@
#if ENABLED(DUAL_X_CARRIAGE)
#if EXTRUDERS == 1
#error "DUAL_X_CARRIAGE requires 2 (or more) extruders."
#elif ENABLED(COREXY) || ENABLED(COREXZ)
#error "DUAL_X_CARRIAGE cannot be used with COREXY or COREXZ."
#elif CORE_IS_XY || CORE_IS_XZ
#error "DUAL_X_CARRIAGE cannot be used with COREXY, COREYX, COREXZ, or COREZX."
#elif !HAS_X2_ENABLE || !HAS_X2_STEP || !HAS_X2_DIR
#error "DUAL_X_CARRIAGE requires X2 stepper pins to be defined."
#elif !HAS_X_MAX
@@ -505,14 +695,14 @@
*/
#if HAS_AUTO_FAN
#if HAS_FAN0
#if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN
#error "You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN."
#elif EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN
#error "You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN."
#elif EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN
#error "You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN."
#elif EXTRUDER_3_AUTO_FAN_PIN == FAN_PIN
#error "You cannot set EXTRUDER_3_AUTO_FAN_PIN equal to FAN_PIN."
#if E0_AUTO_FAN_PIN == FAN_PIN
#error "You cannot set E0_AUTO_FAN_PIN equal to FAN_PIN."
#elif E1_AUTO_FAN_PIN == FAN_PIN
#error "You cannot set E1_AUTO_FAN_PIN equal to FAN_PIN."
#elif E2_AUTO_FAN_PIN == FAN_PIN
#error "You cannot set E2_AUTO_FAN_PIN equal to FAN_PIN."
#elif E3_AUTO_FAN_PIN == FAN_PIN
#error "You cannot set E3_AUTO_FAN_PIN equal to FAN_PIN."
#endif
#endif
#endif
@@ -522,14 +712,14 @@
#endif
#if HAS_CONTROLLERFAN
#if EXTRUDER_0_AUTO_FAN_PIN == CONTROLLERFAN_PIN
#error "You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN."
#elif EXTRUDER_1_AUTO_FAN_PIN == CONTROLLERFAN_PIN
#error "You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN."
#elif EXTRUDER_2_AUTO_FAN_PIN == CONTROLLERFAN_PIN
#error "You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN."
#elif EXTRUDER_3_AUTO_FAN_PIN == CONTROLLERFAN_PIN
#error "You cannot set EXTRUDER_3_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN."
#if E0_AUTO_FAN_PIN == CONTROLLERFAN_PIN
#error "You cannot set E0_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN."
#elif E1_AUTO_FAN_PIN == CONTROLLERFAN_PIN
#error "You cannot set E1_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN."
#elif E2_AUTO_FAN_PIN == CONTROLLERFAN_PIN
#error "You cannot set E2_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN."
#elif E3_AUTO_FAN_PIN == CONTROLLERFAN_PIN
#error "You cannot set E3_AUTO_FAN_PIN equal to CONTROLLERFAN_PIN."
#endif
#endif
@@ -594,6 +784,13 @@
#error "TEMP_SENSOR_1 is required with TEMP_SENSOR_1_AS_REDUNDANT."
#endif
/**
* Temperature status LEDs
*/
#if ENABLED(TEMP_STAT_LEDS) && !PIN_EXISTS(STAT_LED_RED) && !PIN_EXISTS(STAT_LED_BLUE)
#error "TEMP_STAT_LEDS requires STAT_LED_RED_PIN or STAT_LED_BLUE_PIN, preferably both."
#endif
/**
* Basic 2-nozzle duplication mode
*/
@@ -632,105 +829,219 @@
* Endstops
*/
#if DISABLED(USE_XMIN_PLUG) && DISABLED(USE_XMAX_PLUG) && !(ENABLED(Z_DUAL_ENDSTOPS) && Z2_USE_ENDSTOP >= _XMAX_ && Z2_USE_ENDSTOP <= _XMIN_)
#error "You must enable USE_XMIN_PLUG or USE_XMAX_PLUG"
#error "You must enable USE_XMIN_PLUG or USE_XMAX_PLUG."
#elif DISABLED(USE_YMIN_PLUG) && DISABLED(USE_YMAX_PLUG) && !(ENABLED(Z_DUAL_ENDSTOPS) && Z2_USE_ENDSTOP >= _YMAX_ && Z2_USE_ENDSTOP <= _YMIN_)
#error "You must enable USE_YMIN_PLUG or USE_YMAX_PLUG"
#error "You must enable USE_YMIN_PLUG or USE_YMAX_PLUG."
#elif DISABLED(USE_ZMIN_PLUG) && DISABLED(USE_ZMAX_PLUG) && !(ENABLED(Z_DUAL_ENDSTOPS) && Z2_USE_ENDSTOP >= _ZMAX_ && Z2_USE_ENDSTOP <= _ZMIN_)
#error "You must enable USE_ZMIN_PLUG or USE_ZMAX_PLUG"
#elif ENABLED(Z_DUAL_ENDSTOPS) && !Z2_USE_ENDSTOP
#error "You must set Z2_USE_ENDSTOP with Z_DUAL_ENDSTOPS"
#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 ENABLED(DELTA)
#error "Z_DUAL_ENDSTOPS is not compatible with DELTA."
#endif
#elif !IS_SCARA
#if X_HOME_DIR < 0 && DISABLED(USE_XMIN_PLUG)
#error "Enable USE_XMIN_PLUG when homing X to MIN."
#elif X_HOME_DIR > 0 && DISABLED(USE_XMAX_PLUG)
#error "Enable USE_XMAX_PLUG when homing X to MAX."
#elif Y_HOME_DIR < 0 && DISABLED(USE_YMIN_PLUG)
#error "Enable USE_YMIN_PLUG when homing Y to MIN."
#elif Y_HOME_DIR > 0 && DISABLED(USE_YMAX_PLUG)
#error "Enable USE_YMAX_PLUG when homing Y to MAX."
#elif Z_HOME_DIR < 0 && DISABLED(USE_ZMIN_PLUG)
#error "Enable USE_ZMIN_PLUG when homing Z to MIN."
#elif Z_HOME_DIR > 0 && DISABLED(USE_ZMAX_PLUG)
#error "Enable USE_ZMAX_PLUG when homing Z to MAX."
#endif
#endif
/**
* emergency-command parser
*/
#if ENABLED(EMERGENCY_PARSER) && ENABLED(USBCON)
#if ENABLED(EMERGENCY_PARSER) && defined(USBCON)
#error "EMERGENCY_PARSER does not work on boards with AT90USB processors (USBCON)."
#endif
/**
* Warnings for old configurations
/**
* I2C bus
*/
#if WATCH_TEMP_PERIOD > 500
#error "WATCH_TEMP_PERIOD now uses seconds instead of milliseconds."
#elif DISABLED(THERMAL_PROTECTION_HOTENDS) && (defined(WATCH_TEMP_PERIOD) || defined(THERMAL_PROTECTION_PERIOD))
#error "Thermal Runaway Protection for hotends is now enabled with THERMAL_PROTECTION_HOTENDS."
#elif DISABLED(THERMAL_PROTECTION_BED) && defined(THERMAL_PROTECTION_BED_PERIOD)
#error "Thermal Runaway Protection for the bed is now enabled with THERMAL_PROTECTION_BED."
#elif ENABLED(COREXZ) && ENABLED(Z_LATE_ENABLE)
#error "Z_LATE_ENABLE can't be used with COREXZ."
#elif defined(X_HOME_RETRACT_MM)
#error "[XYZ]_HOME_RETRACT_MM settings have been renamed [XYZ]_HOME_BUMP_MM."
#elif defined(BEEPER)
#error "BEEPER is now BEEPER_PIN. Please update your pins definitions."
#elif defined(SDCARDDETECT)
#error "SDCARDDETECT is now SD_DETECT_PIN. Please update your pins definitions."
#elif defined(SDCARDDETECTINVERTED)
#error "SDCARDDETECTINVERTED is now SD_DETECT_INVERTED. Please update your configuration."
#elif defined(BTENABLED)
#error "BTENABLED is now BLUETOOTH. Please update your configuration."
#elif defined(CUSTOM_MENDEL_NAME)
#error "CUSTOM_MENDEL_NAME is now CUSTOM_MACHINE_NAME. Please update your configuration."
#elif defined(HAS_AUTOMATIC_VERSIONING)
#error "HAS_AUTOMATIC_VERSIONING is now USE_AUTOMATIC_VERSIONING. Please update your configuration."
#elif defined(ENABLE_AUTO_BED_LEVELING)
#error "ENABLE_AUTO_BED_LEVELING is now AUTO_BED_LEVELING_FEATURE. Please update your configuration."
#elif defined(SDSLOW)
#error "SDSLOW deprecated. Set SPI_SPEED to SPI_HALF_SPEED instead."
#elif defined(SDEXTRASLOW)
#error "SDEXTRASLOW deprecated. Set SPI_SPEED to SPI_QUARTER_SPEED instead."
#elif defined(FILAMENT_SENSOR)
#error "FILAMENT_SENSOR is deprecated. Use FILAMENT_WIDTH_SENSOR instead."
#elif defined(DISABLE_MAX_ENDSTOPS) || defined(DISABLE_MIN_ENDSTOPS)
#error "DISABLE_MAX_ENDSTOPS and DISABLE_MIN_ENDSTOPS deprecated. Use individual USE_*_PLUG options instead."
#elif ENABLED(Z_DUAL_ENDSTOPS) && !defined(Z2_USE_ENDSTOP)
#error "Z_DUAL_ENDSTOPS settings are simplified. Just set Z2_USE_ENDSTOP to the endstop you want to repurpose for Z2"
#elif defined(LANGUAGE_INCLUDE)
#error "LANGUAGE_INCLUDE has been replaced by LCD_LANGUAGE. Please update your configuration."
#elif defined(EXTRUDER_OFFSET_X) || defined(EXTRUDER_OFFSET_Y)
#error "EXTRUDER_OFFSET_[XY] is deprecated. Use HOTEND_OFFSET_[XY] instead."
#elif defined(PID_PARAMS_PER_EXTRUDER)
#error "PID_PARAMS_PER_EXTRUDER is deprecated. Use PID_PARAMS_PER_HOTEND instead."
#elif defined(EXTRUDER_WATTS) || defined(BED_WATTS)
#error "EXTRUDER_WATTS and BED_WATTS are deprecated. Remove them from your configuration."
#elif defined(SERVO_ENDSTOP_ANGLES)
#error "SERVO_ENDSTOP_ANGLES is deprecated. Use Z_SERVO_ANGLES instead."
#elif defined(X_ENDSTOP_SERVO_NR) || defined(Y_ENDSTOP_SERVO_NR)
#error "X_ENDSTOP_SERVO_NR and Y_ENDSTOP_SERVO_NR are deprecated and should be removed."
#elif defined(XY_TRAVEL_SPEED)
#error "XY_TRAVEL_SPEED is deprecated. Use XY_PROBE_SPEED instead."
#elif defined(PROBE_SERVO_DEACTIVATION_DELAY)
#error "PROBE_SERVO_DEACTIVATION_DELAY is deprecated. Use DEACTIVATE_SERVOS_AFTER_MOVE instead."
#elif defined(SERVO_DEACTIVATION_DELAY)
#error "SERVO_DEACTIVATION_DELAY is deprecated. Use SERVO_DELAY instead."
#elif ENABLED(FILAMENTCHANGEENABLE)
#error "FILAMENTCHANGEENABLE is now FILAMENT_CHANGE_FEATURE. Please update your configuration."
#elif defined(PLA_PREHEAT_HOTEND_TEMP)
#error "PLA_PREHEAT_HOTEND_TEMP is now PREHEAT_1_TEMP_HOTEND. Please update your configuration."
#elif defined(PLA_PREHEAT_HPB_TEMP)
#error "PLA_PREHEAT_HPB_TEMP is now PREHEAT_1_TEMP_BED. Please update your configuration."
#elif defined(PLA_PREHEAT_FAN_SPEED)
#error "PLA_PREHEAT_FAN_SPEED is now PREHEAT_1_FAN_SPEED. Please update your configuration."
#elif defined(ABS_PREHEAT_HOTEND_TEMP)
#error "ABS_PREHEAT_HOTEND_TEMP is now PREHEAT_2_TEMP_HOTEND. Please update your configuration."
#elif defined(ABS_PREHEAT_HPB_TEMP)
#error "ABS_PREHEAT_HPB_TEMP is now PREHEAT_2_TEMP_BED. Please update your configuration."
#elif defined(ABS_PREHEAT_FAN_SPEED)
#error "ABS_PREHEAT_FAN_SPEED is now PREHEAT_2_FAN_SPEED. Please update your configuration."
#elif defined(ENDSTOPS_ONLY_FOR_HOMING)
#error "ENDSTOPS_ONLY_FOR_HOMING is deprecated. Use (disable) ENDSTOPS_ALWAYS_ON_DEFAULT instead."
#elif defined(HOMING_FEEDRATE)
#error "HOMING_FEEDRATE is deprecated. Set individual rates with HOMING_FEEDRATE_(XY|Z|E) instead."
#elif defined(MANUAL_HOME_POSITIONS)
#error "MANUAL_HOME_POSITIONS is deprecated. Set MANUAL_[XYZ]_HOME_POS as-needed instead."
#elif defined(PID_ADD_EXTRUSION_RATE)
#error "PID_ADD_EXTRUSION_RATE is now PID_EXTRUSION_SCALING and is DISABLED by default. Are you sure you want to use this option? Please update your configuration."
#elif defined(Z_RAISE_BEFORE_HOMING)
#error "Z_RAISE_BEFORE_HOMING is now Z_HOMING_HEIGHT. Please update your configuration."
#elif defined(MIN_Z_HEIGHT_FOR_HOMING)
#error "MIN_Z_HEIGHT_FOR_HOMING is now Z_HOMING_HEIGHT. Please update your configuration."
#elif defined(Z_RAISE_BEFORE_PROBING) || defined(Z_RAISE_AFTER_PROBING)
#error "Z_RAISE_(BEFORE|AFTER)_PROBING are deprecated. Use Z_PROBE_DEPLOY_HEIGHT instead."
#elif defined(Z_RAISE_PROBE_DEPLOY_STOW) || defined(Z_RAISE_BETWEEN_PROBINGS)
#error "Z_RAISE_PROBE_DEPLOY_STOW and Z_RAISE_BETWEEN_PROBINGS are now Z_PROBE_DEPLOY_HEIGHT and Z_PROBE_TRAVEL_HEIGHT Please update your configuration."
#if ENABLED(EXPERIMENTAL_I2CBUS) && I2C_SLAVE_ADDRESS > 0
#if I2C_SLAVE_ADDRESS < 8
#error "I2C_SLAVE_ADDRESS can't be less than 8. (Addresses 0 - 7 are reserved.)"
#elif I2C_SLAVE_ADDRESS > 127
#error "I2C_SLAVE_ADDRESS can't be over 127. (Only 7 bits allowed.)"
#endif
#endif
/**
* G38 Probe Target
*/
#if ENABLED(G38_PROBE_TARGET)
#if !HAS_BED_PROBE
#error "G38_PROBE_TARGET requires a bed probe."
#elif !IS_CARTESIAN
#error "G38_PROBE_TARGET requires a Cartesian machine."
#endif
#endif
/**
* RGB_LED Requirements
*/
#if ENABLED(RGB_LED)
#if !(PIN_EXISTS(RGB_LED_R) && PIN_EXISTS(RGB_LED_G) && PIN_EXISTS(RGB_LED_B))
#error "RGB_LED requires RGB_LED_R_PIN, RGB_LED_G_PIN, and RGB_LED_B_PIN."
#elif ENABLED(BLINKM)
#error "RGB_LED and BLINKM are currently incompatible (both use M150)."
#endif
#endif
/**
* Auto Fan check for PWM pins
*/
#if HAS_AUTO_FAN && EXTRUDER_AUTO_FAN_SPEED != 255
#define AF_ERR_SUFF "_AUTO_FAN_PIN is not a PWM pin. Set EXTRUDER_AUTO_FAN_SPEED to 255."
#if HAS_AUTO_FAN_0
static_assert(GET_TIMER(E0_AUTO_FAN_PIN), "E0" AF_ERR_SUFF);
#elif HAS_AUTO_FAN_1
static_assert(GET_TIMER(E1_AUTO_FAN_PIN), "E1" AF_ERR_SUFF);
#elif HAS_AUTO_FAN_2
static_assert(GET_TIMER(E2_AUTO_FAN_PIN), "E2" AF_ERR_SUFF);
#elif HAS_AUTO_FAN_3
static_assert(GET_TIMER(E3_AUTO_FAN_PIN), "E3" AF_ERR_SUFF);
#endif
#endif
/**
* Make sure only one display is enabled
*
* Note: BQ_LCD_SMART_CONTROLLER => REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
* REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER => REPRAP_DISCOUNT_SMART_CONTROLLER
* SAV_3DGLCD => U8GLIB_SH1106 => ULTIMAKERCONTROLLER
* miniVIKI => ULTIMAKERCONTROLLER
* VIKI2 => ULTIMAKERCONTROLLER
* ELB_FULL_GRAPHIC_CONTROLLER => ULTIMAKERCONTROLLER
* PANEL_ONE => ULTIMAKERCONTROLLER
*/
#define COUNT_LCD_1 0
#if ENABLED(ULTIMAKERCONTROLLER) \
&& DISABLED(SAV_3DGLCD) && DISABLED(miniVIKI) && DISABLED(VIKI2) \
&& DISABLED(ELB_FULL_GRAPHIC_CONTROLLER) && DISABLED(PANEL_ONE)
#define COUNT_LCD_2 INCREMENT(COUNT_LCD_1)
#else
#define COUNT_LCD_2 COUNT_LCD_1
#endif
#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) && DISABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
#define COUNT_LCD_3 INCREMENT(COUNT_LCD_2)
#else
#define COUNT_LCD_3 COUNT_LCD_2
#endif
#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) && DISABLED(BQ_LCD_SMART_CONTROLLER)
#define COUNT_LCD_4 INCREMENT(COUNT_LCD_3)
#else
#define COUNT_LCD_4 COUNT_LCD_3
#endif
#if ENABLED(CARTESIO_UI)
#define COUNT_LCD_5 INCREMENT(COUNT_LCD_4)
#else
#define COUNT_LCD_5 COUNT_LCD_4
#endif
#if ENABLED(PANEL_ONE)
#define COUNT_LCD_6 INCREMENT(COUNT_LCD_5)
#else
#define COUNT_LCD_6 COUNT_LCD_5
#endif
#if ENABLED(MAKRPANEL)
#define COUNT_LCD_7 INCREMENT(COUNT_LCD_6)
#else
#define COUNT_LCD_7 COUNT_LCD_6
#endif
#if ENABLED(REPRAPWORLD_GRAPHICAL_LCD)
#define COUNT_LCD_8 INCREMENT(COUNT_LCD_7)
#else
#define COUNT_LCD_8 COUNT_LCD_7
#endif
#if ENABLED(VIKI2)
#define COUNT_LCD_9 INCREMENT(COUNT_LCD_8)
#else
#define COUNT_LCD_9 COUNT_LCD_8
#endif
#if ENABLED(miniVIKI)
#define COUNT_LCD_10 INCREMENT(COUNT_LCD_9)
#else
#define COUNT_LCD_10 COUNT_LCD_9
#endif
#if ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
#define COUNT_LCD_11 INCREMENT(COUNT_LCD_10)
#else
#define COUNT_LCD_11 COUNT_LCD_10
#endif
#if ENABLED(G3D_PANEL)
#define COUNT_LCD_12 INCREMENT(COUNT_LCD_11)
#else
#define COUNT_LCD_12 COUNT_LCD_11
#endif
#if ENABLED(MINIPANEL)
#define COUNT_LCD_13 INCREMENT(COUNT_LCD_12)
#else
#define COUNT_LCD_13 COUNT_LCD_12
#endif
#if ENABLED(REPRAPWORLD_KEYPAD) && DISABLED(CARTESIO_UI)
#define COUNT_LCD_14 INCREMENT(COUNT_LCD_13)
#else
#define COUNT_LCD_14 COUNT_LCD_13
#endif
#if ENABLED(RIGIDBOT_PANEL)
#define COUNT_LCD_15 INCREMENT(COUNT_LCD_14)
#else
#define COUNT_LCD_15 COUNT_LCD_14
#endif
#if ENABLED(RA_CONTROL_PANEL)
#define COUNT_LCD_16 INCREMENT(COUNT_LCD_15)
#else
#define COUNT_LCD_16 COUNT_LCD_15
#endif
#if ENABLED(LCD_I2C_SAINSMART_YWROBOT)
#define COUNT_LCD_17 INCREMENT(COUNT_LCD_16)
#else
#define COUNT_LCD_17 COUNT_LCD_16
#endif
#if ENABLED(LCM1602)
#define COUNT_LCD_18 INCREMENT(COUNT_LCD_17)
#else
#define COUNT_LCD_18 COUNT_LCD_17
#endif
#if ENABLED(LCD_I2C_PANELOLU2)
#define COUNT_LCD_19 INCREMENT(COUNT_LCD_18)
#else
#define COUNT_LCD_19 COUNT_LCD_18
#endif
#if ENABLED(LCD_I2C_VIKI)
#define COUNT_LCD_20 INCREMENT(COUNT_LCD_19)
#else
#define COUNT_LCD_20 COUNT_LCD_19
#endif
#if ENABLED(U8GLIB_SSD1306)
#define COUNT_LCD_21 INCREMENT(COUNT_LCD_20)
#else
#define COUNT_LCD_21 COUNT_LCD_20
#endif
#if ENABLED(SAV_3DLCD)
#define COUNT_LCD_22 INCREMENT(COUNT_LCD_21)
#else
#define COUNT_LCD_22 COUNT_LCD_21
#endif
#if ENABLED(BQ_LCD_SMART_CONTROLLER)
#define COUNT_LCD_23 INCREMENT(COUNT_LCD_22)
#else
#define COUNT_LCD_23 COUNT_LCD_22
#endif
#if ENABLED(SAV_3DGLCD)
#define COUNT_LCD_24 INCREMENT(COUNT_LCD_23)
#else
#define COUNT_LCD_24 COUNT_LCD_23
#endif
#if COUNT_LCD_24 > 1
#error "Please select no more than one LCD controller option."
#endif

View File

@@ -302,16 +302,16 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
// set pin modes
pinMode(chipSelectPin_, OUTPUT);
chipSelectHigh();
pinMode(SPI_MISO_PIN, INPUT);
pinMode(SPI_MOSI_PIN, OUTPUT);
pinMode(SPI_SCK_PIN, OUTPUT);
SET_INPUT(SPI_MISO_PIN);
SET_OUTPUT(SPI_MOSI_PIN);
SET_OUTPUT(SPI_SCK_PIN);
#if DISABLED(SOFTWARE_SPI)
// SS must be in output mode even it is not chip select
pinMode(SS_PIN, OUTPUT);
SET_OUTPUT(SS_PIN);
// set SS high - may be chip select for another SPI device
#if SET_SPI_SS_HIGH
digitalWrite(SS_PIN, HIGH);
WRITE(SS_PIN, HIGH);
#endif // SET_SPI_SS_HIGH
// set SCK rate for initialization commands
spiRate_ = SPI_SD_INIT_RATE;

View File

@@ -674,7 +674,7 @@ bool SdBaseFile::open(SdBaseFile* dirFile,
index = 0;
}
// initialize as empty file
memset(p, 0, sizeof(dir_t));
memset(p, 0, sizeof(*p));
memcpy(p->name, dname, 11);
// set timestamps

View File

@@ -26,17 +26,16 @@
*
* This file is part of the Arduino Sd2Card Library
*/
#ifndef SdFatUtil_h
#define SdFatUtil_h
#include "Marlin.h"
#if ENABLED(SDSUPPORT)
#ifndef SdFatUtil_h
#define SdFatUtil_h
/**
* \file
* \brief Useful utility functions.
*/
#include "Marlin.h"
#include "MarlinSerial.h"
/** Store and print a string in flash memory.*/
#define PgmPrint(x) SerialPrint_P(PSTR(x))
/** Store and print a string in flash memory followed by a CR/LF.*/
@@ -51,7 +50,7 @@ namespace SdFatUtil {
}
using namespace SdFatUtil; // NOLINT
#endif //#define SdFatUtil_h
#endif // SDSUPPORT
#endif
#endif // SdFatUtil_h

View File

@@ -33,6 +33,7 @@
#define BOARD_CNCONTROLS_12 112 // Cartesio CN Controls V12
#define BOARD_CHEAPTRONIC 2 // Cheaptronic v1.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_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)
@@ -77,6 +78,7 @@
#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

View File

@@ -109,7 +109,8 @@ class Buzzer {
this->tick();
thermalManager.manage_heater();
}
this->buffer.enqueue((tone_t) { duration, frequency });
tone_t tone = { duration, frequency };
this->buffer.enqueue(tone);
}
/**

View File

@@ -24,7 +24,6 @@
#include "ultralcd.h"
#include "stepper.h"
#include "temperature.h"
#include "language.h"
#include "Marlin.h"
@@ -32,15 +31,12 @@
#if ENABLED(SDSUPPORT)
CardReader::CardReader() {
sdprinting = cardOK = saving = logging = false;
filesize = 0;
sdpos = 0;
sdprinting = false;
cardOK = false;
saving = false;
logging = false;
workDirDepth = 0;
file_subcall_ctr = 0;
memset(workDirParents, 0, sizeof(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_index = 0;
@@ -117,7 +113,7 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
if (pn0 == DIR_NAME_DELETED || pn0 == '.') continue;
if (longFilename[0] == '.') continue;
if (!DIR_IS_FILE_OR_SUBDIR(&p)) continue;
if (!DIR_IS_FILE_OR_SUBDIR(&p) || (p.attributes & DIR_ATT_HIDDEN)) continue;
filenameIsDir = DIR_IS_SUBDIR(&p);
@@ -276,19 +272,12 @@ void CardReader::openAndPrintFile(const char *name) {
}
void CardReader::startFileprint() {
if (cardOK)
sdprinting = true;
}
void CardReader::pauseSDPrint() {
if (sdprinting) sdprinting = false;
if (cardOK) sdprinting = true;
}
void CardReader::stopSDPrint() {
if (sdprinting) {
sdprinting = false;
file.close();
}
sdprinting = false;
if (isFileOpen()) file.close();
}
void CardReader::openLogFile(char* name) {
@@ -310,8 +299,11 @@ void CardReader::getAbsFilename(char *t) {
}
void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
if (!cardOK) return;
if (file.isOpen()) { //replacing current file by new file, or subfile call
uint8_t doing = 0;
if (isFileOpen()) { //replacing current file by new file, or subfile call
if (push_current) {
if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) {
SERIAL_ERROR_START;
@@ -321,40 +313,39 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
return;
}
SERIAL_ECHO_START;
SERIAL_ECHOPGM("SUBROUTINE CALL target:\"");
SERIAL_ECHO(name);
SERIAL_ECHOPGM("\" parent:\"");
//store current filename and position
// Store current filename and position
getAbsFilename(proc_filenames[file_subcall_ctr]);
SERIAL_ECHO(proc_filenames[file_subcall_ctr]);
SERIAL_ECHOPGM("\" pos");
SERIAL_ECHOLN(sdpos);
SERIAL_ECHO_START;
SERIAL_ECHOPAIR("SUBROUTINE CALL target:\"", name);
SERIAL_ECHOPAIR("\" parent:\"", proc_filenames[file_subcall_ctr]);
SERIAL_ECHOLNPAIR("\" pos", sdpos);
filespos[file_subcall_ctr] = sdpos;
file_subcall_ctr++;
}
else {
SERIAL_ECHO_START;
SERIAL_ECHOPGM("Now doing file: ");
SERIAL_ECHOLN(name);
doing = 1;
}
file.close();
}
else { //opening fresh file
file_subcall_ctr = 0; //resetting procedure depth in case user cancels print while in procedure
else { // Opening fresh file
doing = 2;
file_subcall_ctr = 0; // Reset procedure depth in case user cancels print while in procedure
}
if (doing) {
SERIAL_ECHO_START;
SERIAL_ECHOPGM("Now fresh file: ");
SERIAL_ECHOLN(name);
SERIAL_ECHOPGM("Now ");
SERIAL_ECHO(doing == 1 ? "doing" : "fresh");
SERIAL_ECHOLNPAIR(" file: ", name);
}
sdprinting = false;
stopSDPrint();
SdFile myDir;
curDir = &root;
char *fname = name;
char *dirname_start, *dirname_end;
if (name[0] == '/') {
dirname_start = &name[1];
while (dirname_start != NULL) {
@@ -395,8 +386,7 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
if (file.open(curDir, fname, O_READ)) {
filesize = file.fileSize();
SERIAL_PROTOCOLPAIR(MSG_SD_FILE_OPENED, fname);
SERIAL_PROTOCOLPAIR(MSG_SD_SIZE, filesize);
SERIAL_EOL;
SERIAL_PROTOCOLLNPAIR(MSG_SD_SIZE, filesize);
sdpos = 0;
SERIAL_PROTOCOLLNPGM(MSG_SD_FILE_SELECTED);
@@ -417,8 +407,7 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
}
else {
saving = true;
SERIAL_PROTOCOLPAIR(MSG_SD_WRITE_TO_FILE, name);
SERIAL_EOL;
SERIAL_PROTOCOLLNPAIR(MSG_SD_WRITE_TO_FILE, name);
lcd_setstatus(fname);
}
}
@@ -427,8 +416,7 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) {
void CardReader::removeFile(char* name) {
if (!cardOK) return;
file.close();
sdprinting = false;
stopSDPrint();
SdFile myDir;
curDir = &root;
@@ -449,6 +437,7 @@ void CardReader::removeFile(char* name) {
if (!myDir.open(curDir, subdirname, O_READ)) {
SERIAL_PROTOCOLPAIR("open failed, File: ", subdirname);
SERIAL_PROTOCOLCHAR('.');
SERIAL_EOL;
return;
}
else {

View File

@@ -51,7 +51,6 @@ public:
void release();
void openAndPrintFile(const char *name);
void startFileprint();
void pauseSDPrint();
void stopSDPrint();
void getStatus();
void printingHasFinished();
@@ -70,6 +69,7 @@ public:
void updir();
void setroot();
FORCE_INLINE void pauseSDPrint() { sdprinting = false; }
FORCE_INLINE bool isFileOpen() { return file.isOpen(); }
FORCE_INLINE bool eof() { return sdpos >= filesize; }
FORCE_INLINE int16_t get() { sdpos = file.curPosition(); return (int16_t)file.read(); }

File diff suppressed because it is too large Load Diff

View File

@@ -26,6 +26,7 @@
#include "MarlinConfig.h"
void Config_ResetDefault();
void Config_StoreSettings();
#if DISABLED(DISABLE_M503)
void Config_PrintSettings(bool forReplay=false);
@@ -34,10 +35,8 @@ void Config_ResetDefault();
#endif
#if ENABLED(EEPROM_SETTINGS)
void Config_StoreSettings();
void Config_RetrieveSettings();
#else
FORCE_INLINE void Config_StoreSettings() {}
FORCE_INLINE void Config_RetrieveSettings() { Config_ResetDefault(); Config_PrintSettings(); }
#endif

View File

@@ -31,10 +31,11 @@
*/
#include "dac_mcp4728.h"
#include "enum.h"
#if ENABLED(DAC_STEPPER_CURRENT)
uint16_t mcp4728_values[4];
uint16_t mcp4728_values[XYZE];
/**
* Begin I2C, get current values (input register and eeprom) of mcp4728
@@ -42,16 +43,13 @@ uint16_t mcp4728_values[4];
void mcp4728_init() {
Wire.begin();
Wire.requestFrom(int(DAC_DEV_ADDRESS), 24);
while(Wire.available()) {
int deviceID = Wire.read();
int hiByte = Wire.read();
int loByte = Wire.read();
while (Wire.available()) {
char deviceID = Wire.read(),
hiByte = Wire.read(),
loByte = Wire.read();
int isEEPROM = (deviceID & 0B00001000) >> 3;
int channel = (deviceID & 0B00110000) >> 4;
if (isEEPROM != 1) {
mcp4728_values[channel] = word((hiByte & 0B00001111), loByte);
}
if (!(deviceID & 0x08))
mcp4728_values[(deviceID & 0x30) >> 4] = word((hiByte & 0x0F), loByte);
}
}
@@ -63,6 +61,7 @@ uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value) {
mcp4728_values[channel] = value;
return mcp4728_fastWrite();
}
/**
* Write all input resistor values to EEPROM using SequencialWrite method.
* This will update both input register and EEPROM value
@@ -71,9 +70,9 @@ uint8_t mcp4728_analogWrite(uint8_t channel, uint16_t value) {
uint8_t mcp4728_eepromWrite() {
Wire.beginTransmission(DAC_DEV_ADDRESS);
Wire.write(SEQWRITE);
for (uint8_t channel=0; channel <= 3; channel++) {
Wire.write(DAC_STEPPER_VREF << 7 | 0 << 5 | DAC_STEPPER_GAIN << 4 | highByte(mcp4728_values[channel]));
Wire.write(lowByte(mcp4728_values[channel]));
LOOP_XYZE(i) {
Wire.write(DAC_STEPPER_VREF << 7 | DAC_STEPPER_GAIN << 4 | highByte(mcp4728_values[i]));
Wire.write(lowByte(mcp4728_values[i]));
}
return Wire.endTransmission();
}
@@ -83,7 +82,7 @@ uint8_t mcp4728_eepromWrite() {
*/
uint8_t mcp4728_setVref_all(uint8_t value) {
Wire.beginTransmission(DAC_DEV_ADDRESS);
Wire.write(VREFWRITE | value << 3 | value << 2 | value << 1 | value);
Wire.write(VREFWRITE | (value ? 0x0F : 0x00));
return Wire.endTransmission();
}
/**
@@ -91,12 +90,12 @@ uint8_t mcp4728_setVref_all(uint8_t value) {
*/
uint8_t mcp4728_setGain_all(uint8_t value) {
Wire.beginTransmission(DAC_DEV_ADDRESS);
Wire.write(GAINWRITE | value << 3 | value << 2 | value << 1 | value);
Wire.write(GAINWRITE | (value ? 0x0F : 0x00));
return Wire.endTransmission();
}
/**
* Return Input Regiter value
* Return Input Register value
*/
uint16_t mcp4728_getValue(uint8_t channel) { return mcp4728_values[channel]; }
@@ -105,13 +104,27 @@ uint16_t mcp4728_getValue(uint8_t channel) { return mcp4728_values[channel]; }
* Return Vout
*
uint16_t mcp4728_getVout(uint8_t channel) {
uint32_t vref = 2048;
uint32_t vOut = (vref * mcp4728_values[channel] * (_DAC_STEPPER_GAIN + 1)) / 4096;
uint32_t vref = 2048,
vOut = (vref * mcp4728_values[channel] * (_DAC_STEPPER_GAIN + 1)) / 4096;
if (vOut > defaultVDD) vOut = defaultVDD;
return vOut;
}
*/
/**
* Returns DAC values as a 0-100 percentage of drive strength
*/
uint16_t mcp4728_getDrvPct(uint8_t channel) { return uint16_t(100.0 * mcp4728_values[channel] / (DAC_STEPPER_MAX) + 0.5); }
/**
* Receives all Drive strengths as 0-100 percent values, updates
* DAC Values array and calls fastwrite to update the DAC.
*/
void mcp4728_setDrvPct(uint16_t pct[XYZE]) {
LOOP_XYZE(i) mcp4728_values[i] = 0.01 * pct[i] * (DAC_STEPPER_MAX);
mcp4728_fastWrite();
}
/**
* FastWrite input register values - All DAC ouput update. refer to DATASHEET 5.6.1
* DAC Input and PowerDown bits update.
@@ -119,9 +132,9 @@ uint16_t mcp4728_getVout(uint8_t channel) {
*/
uint8_t mcp4728_fastWrite() {
Wire.beginTransmission(DAC_DEV_ADDRESS);
for (uint8_t channel=0; channel <= 3; channel++) {
Wire.write(highByte(mcp4728_values[channel]));
Wire.write(lowByte(mcp4728_values[channel]));
LOOP_XYZE(i) {
Wire.write(highByte(mcp4728_values[i]));
Wire.write(lowByte(mcp4728_values[i]));
}
return Wire.endTransmission();
}

View File

@@ -24,15 +24,15 @@
* Arduino library for MicroChip MCP4728 I2C D/A converter.
*/
#ifndef mcp4728_h
#define mcp4728_h
#ifndef DAC_MCP4728_H
#define DAC_MCP4728_H
#include "MarlinConfig.h"
#if ENABLED(DAC_STEPPER_CURRENT)
#include "Wire.h"
#define defaultVDD 5000
#define defaultVDD DAC_STEPPER_MAX //was 5000 but differs with internal Vref
#define BASE_ADDR 0x60
#define RESET 0B00000110
#define WAKE 0B00001001
@@ -59,7 +59,8 @@ uint8_t mcp4728_setGain_all(uint8_t value);
uint16_t mcp4728_getValue(uint8_t channel);
uint8_t mcp4728_fastWrite();
uint8_t mcp4728_simpleCommand(byte simpleCommand);
uint16_t mcp4728_getDrvPct(uint8_t channel);
void mcp4728_setDrvPct(uint16_t pct[XYZE]);
#endif
#endif
#endif // DAC_MCP4728_H

View File

@@ -0,0 +1,197 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/*
Fontname: ISO10646-1-tr
Copyright: public domain
Capital A Height: 7, '1' Height: 7
Calculated Max Values w= 5 h= 9 x= 2 y= 7 dx= 6 dy= 0 ascent= 8 len= 9
Font Bounding box w= 6 h= 9 x= 0 y=-2
Calculated Min Values x= 0 y=-1 dx= 0 dy= 0
Pure Font ascent = 7 descent=-1
X Font ascent = 7 descent=-1
Max Font ascent = 8 descent=-1
*/
#include "U8glib.h"
const u8g_fntpgm_uint8_t ISO10646_TR[2591] U8G_SECTION(".progmem.ISO10646_TR") = {
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,
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,0,0,0,6,0,
0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
0,0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,
6,0,0,0,0,0,6,0,0,0,0,0,6,0,0,0,
0,0,6,0,0,0,0,0,6,0,0,0,0,0,6,0,
0,1,7,7,6,2,0,128,0,128,128,128,128,128,5,7,
7,6,0,0,32,112,168,160,168,112,32,5,7,7,6,0,
0,48,64,64,224,64,80,168,5,5,5,6,0,0,136,112,
80,112,136,5,7,7,6,0,0,136,80,32,248,32,248,32,
1,7,7,6,2,0,128,128,128,0,128,128,128,5,8,8,
6,0,0,48,72,32,80,80,32,144,96,3,1,1,6,1,
7,160,5,7,7,6,0,0,248,136,184,184,184,136,248,5,
7,7,6,0,1,112,8,120,136,120,0,248,5,5,5,6,
0,1,40,80,160,80,40,5,3,3,6,0,1,248,8,8,
2,2,2,6,2,6,64,128,5,7,7,6,0,0,248,136,
168,136,152,168,248,5,1,1,6,0,6,248,4,4,4,6,
0,3,96,144,144,96,5,7,7,6,0,0,32,32,248,32,
32,0,248,4,5,5,6,0,3,96,144,32,64,240,3,5,
5,6,0,3,224,32,224,32,224,2,2,2,6,2,6,64,
128,5,8,8,6,0,255,136,136,136,136,152,232,128,128,5,
7,7,6,0,0,120,152,152,120,24,24,24,2,2,2,6,
2,2,192,192,2,2,2,6,2,255,64,128,3,5,5,6,
0,3,64,192,64,64,224,5,7,7,6,0,1,112,136,136,
136,112,0,248,5,5,5,6,0,1,160,80,40,80,160,5,
7,7,6,0,0,136,144,168,88,184,8,8,5,7,7,6,
0,0,136,144,184,72,152,32,56,5,8,8,6,0,0,192,
64,192,72,216,56,8,8,5,7,7,6,0,0,32,0,32,
64,128,136,112,5,8,8,6,0,0,64,32,0,112,136,248,
136,136,5,8,8,6,0,0,16,32,0,112,136,248,136,136,
5,8,8,6,0,0,32,80,0,112,136,248,136,136,5,8,
8,6,0,0,104,144,0,112,136,248,136,136,5,8,8,6,
0,0,80,0,112,136,136,248,136,136,5,8,8,6,0,0,
32,80,32,112,136,248,136,136,5,7,7,6,0,0,56,96,
160,184,224,160,184,5,8,8,6,0,255,112,136,128,128,136,
112,32,96,5,8,8,6,0,0,64,32,0,248,128,240,128,
248,5,8,8,6,0,0,8,16,0,248,128,240,128,248,5,
8,8,6,0,0,32,80,0,248,128,240,128,248,5,7,7,
6,0,0,80,0,248,128,240,128,248,3,8,8,6,1,0,
128,64,0,224,64,64,64,224,3,8,8,6,1,0,32,64,
0,224,64,64,64,224,3,8,8,6,1,0,64,160,0,224,
64,64,64,224,3,7,7,6,1,0,160,0,224,64,64,64,
224,5,9,9,6,0,255,80,32,112,136,128,184,136,136,112,
5,8,8,6,0,0,104,144,0,136,200,168,152,136,5,8,
8,6,0,0,64,32,112,136,136,136,136,112,5,8,8,6,
0,0,16,32,112,136,136,136,136,112,5,8,8,6,0,0,
32,80,0,112,136,136,136,112,5,8,8,6,0,0,104,144,
0,112,136,136,136,112,5,8,8,6,0,0,80,0,112,136,
136,136,136,112,5,5,5,6,0,1,136,80,32,80,136,5,
8,8,6,0,255,16,112,168,168,168,168,112,64,5,8,8,
6,0,0,64,32,136,136,136,136,136,112,5,8,8,6,0,
0,16,32,136,136,136,136,136,112,5,8,8,6,0,0,32,
80,0,136,136,136,136,112,5,8,8,6,0,0,80,0,136,
136,136,136,136,112,1,7,7,6,2,0,128,0,128,128,128,
128,128,5,9,9,6,0,255,120,128,128,112,8,8,240,32,
96,4,8,8,6,1,255,96,144,144,160,144,144,224,128,5,
8,8,6,0,0,64,32,0,112,8,120,136,120,5,8,8,
6,0,0,16,32,0,112,8,120,136,120,5,8,8,6,0,
0,32,80,0,112,8,120,136,120,5,8,8,6,0,0,104,
144,0,112,8,120,136,120,5,7,7,6,0,0,80,0,112,
8,120,136,120,5,8,8,6,0,0,32,80,32,112,8,120,
136,120,5,6,6,6,0,0,208,40,120,160,168,80,5,7,
7,6,0,255,112,128,128,136,112,32,96,5,8,8,6,0,
0,64,32,0,112,136,248,128,112,5,8,8,6,0,0,16,
32,0,112,136,248,128,112,5,8,8,6,0,0,32,80,0,
112,136,248,128,112,5,7,7,6,0,0,80,0,112,136,248,
128,112,3,8,8,6,1,0,128,64,0,64,192,64,64,224,
3,8,8,6,1,0,32,64,0,64,192,64,64,224,3,8,
8,6,1,0,64,160,0,64,192,64,64,224,3,7,7,6,
1,0,160,0,64,192,64,64,224,5,8,8,6,0,255,80,
32,112,136,136,120,8,112,5,8,8,6,0,0,104,144,0,
176,200,136,136,136,5,8,8,6,0,0,64,32,0,112,136,
136,136,112,5,8,8,6,0,0,16,32,0,112,136,136,136,
112,5,8,8,6,0,0,32,80,0,112,136,136,136,112,5,
8,8,6,0,0,104,144,0,112,136,136,136,112,5,7,7,
6,0,0,80,0,112,136,136,136,112,5,5,5,6,0,1,
32,0,248,0,32,5,7,7,6,0,255,16,112,168,168,168,
112,64,5,8,8,6,0,0,64,32,0,136,136,136,152,104,
5,8,8,6,0,0,16,32,0,136,136,136,152,104,5,8,
8,6,0,0,32,80,0,136,136,136,152,104,5,7,7,6,
0,0,80,0,136,136,136,152,104,1,5,5,6,2,0,128,
128,128,128,128,5,7,7,6,0,255,112,128,112,8,240,32,
96,5,8,8,6,0,255,80,0,136,136,136,120,8,112};

View File

@@ -24,16 +24,16 @@
Fontname: ISO10646_4_Greek
Copyright: A. Hardtung, public domain
Capital A Height: 7, '1' Height: 7
Calculated Max Values w= 5 h=10 x= 2 y= 6 dx= 6 dy= 0 ascent= 8 len=10
Calculated Max Values w= 5 h= 9 x= 2 y= 6 dx= 6 dy= 0 ascent= 8 len= 9
Font Bounding box w= 6 h= 9 x= 0 y=-2
Calculated Min Values x= 0 y=-2 dx= 0 dy= 0
Calculated Min Values x= 0 y=-1 dx= 0 dy= 0
Pure Font ascent = 7 descent=-1
X Font ascent = 7 descent=-1
Max Font ascent = 8 descent=-2
Max Font ascent = 8 descent=-1
*/
#include <U8glib.h>
const u8g_fntpgm_uint8_t ISO10646_Greek_5x7[2728] U8G_SECTION(".progmem.ISO10646_Greek_5x7") = {
0,6,9,0,254,7,1,145,3,32,32,255,255,8,254,7,
const u8g_fntpgm_uint8_t ISO10646_Greek_5x7[2715] U8G_SECTION(".progmem.ISO10646_Greek_5x7") = {
0,6,9,0,254,7,1,145,3,32,32,255,255,8,255,7,
255,0,0,0,6,0,0,1,7,7,6,2,0,128,128,128,
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,
@@ -139,68 +139,67 @@ const u8g_fntpgm_uint8_t ISO10646_Greek_5x7[2728] U8G_SECTION(".progmem.ISO10646
80,80,216,3,8,8,6,1,0,160,0,224,64,64,64,64,
224,5,8,8,6,0,0,80,0,136,136,136,80,32,32,5,
8,8,6,0,0,32,64,8,104,152,144,144,104,5,8,8,
6,0,0,32,64,0,112,136,224,136,112,5,10,10,6,0,
254,32,64,0,112,136,136,136,136,8,8,2,8,8,6,1,
0,64,128,0,128,128,128,128,64,5,8,8,6,0,0,16,
32,80,0,136,136,136,112,5,6,6,6,0,0,8,104,152,
144,144,104,4,7,7,6,0,254,96,144,240,144,224,128,128,
5,6,6,6,0,255,136,72,80,32,32,64,5,6,6,6,
0,0,48,64,112,136,136,112,5,5,5,6,0,0,112,136,
224,136,112,5,9,9,6,0,254,128,112,64,128,128,128,112,
8,112,5,7,7,6,0,254,184,200,136,136,136,8,8,5,
5,5,6,0,0,112,136,248,136,112,3,5,5,6,1,0,
128,128,128,128,96,4,5,5,6,0,0,144,160,192,160,144,
5,6,6,6,0,0,64,32,32,80,80,136,5,7,7,6,
0,254,136,136,136,216,168,128,128,5,5,5,6,0,0,136,
136,80,96,32,5,10,10,6,0,254,128,224,128,112,32,64,
128,112,8,112,5,5,5,6,0,0,112,136,136,136,112,5,
5,5,6,0,0,248,80,80,80,80,5,7,7,6,0,254,
112,136,136,200,176,128,128,5,7,7,6,0,254,48,64,128,
64,48,8,112,5,5,5,6,0,0,104,144,144,144,96,4,
5,5,6,0,0,240,64,64,64,48,5,5,5,6,0,0,
136,136,144,144,224,5,8,8,6,0,254,48,168,168,168,168,
112,32,32,5,6,6,6,0,255,136,80,32,32,80,136,5,
7,7,6,0,254,168,168,168,168,112,32,32,5,5,5,6,
0,0,80,136,136,168,112,4,7,7,6,0,0,160,0,64,
64,64,64,48,5,7,7,6,0,0,80,0,136,136,144,144,
224,4,8,8,6,0,0,32,64,0,96,144,144,144,96,5,
8,8,6,0,0,32,64,0,136,136,144,144,96,5,8,8,
6,0,0,32,64,0,80,136,136,168,112,5,7,7,6,0,
255,144,160,192,160,144,136,16,5,8,8,6,0,0,96,144,
160,128,240,136,136,112,5,7,7,6,0,0,112,80,56,144,
144,144,96,5,6,6,6,0,0,152,80,32,32,32,32,5,
8,8,6,0,0,64,128,152,80,32,32,32,32,5,8,8,
6,0,0,80,0,152,80,32,32,32,32,5,7,7,6,0,
255,48,168,168,168,168,112,32,5,5,5,6,0,0,248,80,
80,80,88,5,6,6,6,0,255,136,80,112,80,136,16,5,
7,7,6,0,255,112,136,136,136,112,32,112,5,6,6,6,
0,255,112,136,136,112,32,112,5,6,6,6,0,0,112,136,
128,112,32,112,5,7,7,6,0,254,8,112,128,128,112,16,
96,5,6,6,6,0,0,248,128,128,240,128,128,4,5,5,
6,0,0,240,128,224,128,128,5,6,6,6,0,0,248,0,
0,112,0,248,4,5,5,6,0,0,64,128,240,16,32,5,
7,7,6,0,0,224,80,40,40,8,8,16,5,7,7,6,
0,0,192,32,80,40,8,8,8,5,8,8,6,0,254,168,
168,168,168,168,88,8,112,5,7,7,6,0,254,168,168,168,
168,88,8,112,5,6,6,6,0,0,104,136,136,120,8,8,
5,6,6,6,0,255,104,136,136,120,8,8,4,8,8,6,
0,254,128,224,144,144,144,144,32,192,5,5,5,6,0,0,
104,144,112,16,224,5,6,6,6,0,0,96,144,16,96,136,
112,4,6,6,6,0,0,96,144,16,96,128,112,5,6,6,
6,0,0,136,80,32,80,136,248,5,5,5,6,0,0,136,
80,32,80,112,5,6,6,6,0,0,120,128,240,136,136,112,
4,5,5,6,0,0,240,128,224,144,96,3,6,6,6,1,
0,64,224,64,64,64,64,3,6,6,6,1,255,64,224,64,
64,64,128,5,5,5,6,0,0,136,80,112,80,136,5,7,
7,6,0,254,112,136,136,136,240,128,112,4,5,5,6,0,
0,112,128,128,128,112,2,8,8,6,1,255,64,0,192,64,
64,64,64,128,5,7,7,6,0,0,112,136,136,248,136,136,
112,4,5,5,6,0,0,112,128,224,128,112,4,5,5,6,
0,0,224,16,112,16,224,5,7,7,6,0,0,128,240,136,
136,136,240,128,4,7,7,6,0,255,128,224,144,144,144,224,
128,5,6,6,6,0,0,112,136,128,128,136,112,5,6,6,
6,0,0,136,216,168,136,136,136,5,7,7,6,0,254,136,
216,168,136,136,128,128,5,8,8,6,0,254,112,136,136,136,
112,64,224,64,5,6,6,6,0,0,112,136,8,8,136,112,
5,6,6,6,0,0,112,136,160,128,136,112,5,6,6,6,
0,0,112,136,40,8,136,112};
6,0,0,32,64,0,112,136,224,136,112,5,9,9,6,0,
255,32,64,0,112,136,136,136,136,8,2,8,8,6,1,0,
64,128,0,128,128,128,128,64,5,8,8,6,0,0,16,32,
80,0,136,136,136,112,5,6,6,6,0,0,8,104,152,144,
144,104,4,6,6,6,0,255,96,144,240,144,224,128,5,6,
6,6,0,255,136,72,80,32,32,64,5,6,6,6,0,0,
48,64,112,136,136,112,5,5,5,6,0,0,112,136,224,136,
112,5,8,8,6,0,255,128,112,64,128,128,112,8,112,5,
6,6,6,0,255,184,200,136,136,136,8,5,5,5,6,0,
0,112,136,248,136,112,3,5,5,6,1,0,128,128,128,128,
96,4,5,5,6,0,0,144,160,192,160,144,5,6,6,6,
0,0,64,32,32,80,80,136,5,6,6,6,0,255,136,136,
136,216,168,128,5,5,5,6,0,0,136,136,80,96,32,5,
9,9,6,0,255,128,224,128,112,32,64,240,8,112,5,5,
5,6,0,0,112,136,136,136,112,5,5,5,6,0,0,248,
80,80,80,80,5,6,6,6,0,255,112,136,136,200,176,128,
5,7,7,6,0,255,48,64,128,64,48,8,112,5,5,5,
6,0,0,104,144,144,144,96,4,5,5,6,0,0,240,64,
64,64,48,5,5,5,6,0,0,136,136,144,144,224,5,7,
7,6,0,255,32,168,168,168,112,32,32,5,6,6,6,0,
255,136,80,32,32,80,136,5,6,6,6,0,255,168,168,168,
168,112,32,5,5,5,6,0,0,80,136,136,168,112,4,7,
7,6,0,0,160,0,64,64,64,64,48,5,7,7,6,0,
0,80,0,136,136,144,144,224,4,8,8,6,0,0,32,64,
0,96,144,144,144,96,5,8,8,6,0,0,32,64,0,136,
136,144,144,96,5,8,8,6,0,0,32,64,0,80,136,136,
168,112,5,7,7,6,0,255,144,160,192,160,144,136,16,5,
8,8,6,0,0,96,144,160,128,240,136,136,112,5,7,7,
6,0,0,112,80,56,144,144,144,96,5,6,6,6,0,0,
152,80,32,32,32,32,5,8,8,6,0,0,64,128,152,80,
32,32,32,32,5,8,8,6,0,0,80,0,152,80,32,32,
32,32,5,7,7,6,0,255,48,168,168,168,168,112,32,5,
5,5,6,0,0,248,80,80,80,88,5,6,6,6,0,255,
136,80,112,80,136,16,5,7,7,6,0,255,112,136,136,136,
112,32,112,5,6,6,6,0,255,112,136,136,112,32,112,5,
6,6,6,0,0,112,136,128,112,32,112,5,7,7,6,0,
255,8,8,112,128,112,16,96,5,6,6,6,0,0,248,128,
128,240,128,128,4,5,5,6,0,0,240,128,224,128,128,5,
6,6,6,0,0,248,0,0,112,0,248,4,5,5,6,0,
0,64,128,240,16,32,5,7,7,6,0,0,224,80,40,40,
8,8,16,5,7,7,6,0,0,192,32,80,40,8,8,8,
5,7,7,6,0,255,168,168,168,168,88,8,112,5,6,6,
6,0,255,168,168,168,88,8,112,5,6,6,6,0,0,104,
136,136,120,8,8,5,6,6,6,0,255,104,136,136,120,8,
8,4,8,8,6,0,255,128,224,144,144,144,144,32,192,5,
5,5,6,0,0,104,144,112,16,224,5,6,6,6,0,0,
96,144,16,96,136,112,4,6,6,6,0,0,96,144,16,96,
128,112,5,6,6,6,0,0,136,80,32,80,136,248,5,5,
5,6,0,0,136,80,32,80,112,5,6,6,6,0,0,120,
128,240,136,136,112,4,5,5,6,0,0,240,128,224,144,96,
3,6,6,6,1,0,64,224,64,64,64,64,3,6,6,6,
1,255,64,224,64,64,64,128,5,5,5,6,0,0,136,80,
112,80,136,5,6,6,6,0,255,112,136,136,240,128,112,4,
5,5,6,0,0,112,128,128,128,112,2,8,8,6,1,255,
64,0,192,64,64,64,64,128,5,7,7,6,0,0,112,136,
136,248,136,136,112,4,5,5,6,0,0,112,128,224,128,112,
4,5,5,6,0,0,224,16,112,16,224,5,7,7,6,0,
0,128,240,136,136,136,240,128,4,7,7,6,0,255,128,224,
144,144,144,224,128,5,6,6,6,0,0,112,136,128,128,136,
112,5,6,6,6,0,0,136,216,168,136,136,136,5,6,6,
6,0,255,136,216,168,136,136,128,5,8,8,6,0,255,112,
136,136,136,112,64,224,64,5,6,6,6,0,0,112,136,8,
8,136,112,5,6,6,6,0,0,112,136,160,128,136,112,5,
6,6,6,0,0,112,136,40,8,136,112};

View File

@@ -141,14 +141,26 @@ struct duration_t {
* @param buffer The array pointed to must be able to accommodate 10 bytes
*
* Output examples:
* 1234567890 (strlen)
* 1193046:59
* 123456789 (strlen)
* 99:59
* 11d 12:33
*/
void toDigital(char *buffer) const {
int h = this->hour() % 24,
m = this->minute() % 60;
sprintf_P(buffer, PSTR("%02i:%02i"), h, m);
uint8_t toDigital(char *buffer, bool with_days=false) const {
uint16_t h = uint16_t(this->hour()),
m = uint16_t(this->minute() % 60UL);
if (with_days) {
uint16_t d = this->day();
sprintf_P(buffer, PSTR("%ud %02u:%02u"), d, h, m);
return d >= 10 ? 8 : 7;
}
else if (h < 100) {
sprintf_P(buffer, PSTR("%02u:%02u"), h % 24, m);
return 5;
}
else {
sprintf_P(buffer, PSTR("%u:%02u"), h, m);
return 6;
}
}
};

206
Marlin/endstop_interrupts.h Normal file
View File

@@ -0,0 +1,206 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/**
* Endstop Interrupts
*
* Without endstop interrupts the endstop pins must be polled continually in
* the stepper-ISR via endstops.update(), most of the time finding no change.
* With this feature endstops.update() is called only when we know that at
* least one endstop has changed state, saving valuable CPU cycles.
*
* This feature only works when all used endstop pins can generate either an
* 'external interrupt' or a 'pin change interrupt'.
*
* Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'.
* (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino)
*/
#ifndef _ENDSTOP_INTERRUPTS_H_
#define _ENDSTOP_INTERRUPTS_H_
/**
* Patch for pins_arduino.h (...\Arduino\hardware\arduino\avr\variants\mega\pins_arduino.h)
*
* These macros for the Arduino MEGA do not include the two connected pins on Port J (D13, D14).
* So we extend them here because these are the normal pins for Y_MIN and Y_MAX on RAMPS.
* There are more PCI-enabled processor pins on Port J, but they are not connected to Arduino MEGA.
*/
#if defined(ARDUINO_AVR_MEGA2560) || defined(ARDUINO_AVR_MEGA)
#undef digitalPinToPCICR
#define digitalPinToPCICR(p) ( (((p) >= 10) && ((p) <= 15)) || \
(((p) >= 50) && ((p) <= 53)) || \
(((p) >= 62) && ((p) <= 69)) ? (&PCICR) : ((uint8_t *)0) )
#undef digitalPinToPCICRbit
#define digitalPinToPCICRbit(p) ( (((p) >= 10) && ((p) <= 13)) || (((p) >= 50) && ((p) <= 53)) ? 0 : \
( (((p) >= 14) && ((p) <= 15)) ? 1 : \
( (((p) >= 62) && ((p) <= 69)) ? 2 : \
0 ) ) )
#undef digitalPinToPCMSK
#define digitalPinToPCMSK(p) ( (((p) >= 10) && ((p) <= 13)) || (((p) >= 50) && ((p) <= 53)) ? (&PCMSK0) : \
( (((p) >= 14) && ((p) <= 15)) ? (&PCMSK1) : \
( (((p) >= 62) && ((p) <= 69)) ? (&PCMSK2) : \
((uint8_t *)0) ) ) )
#undef digitalPinToPCMSKbit
#define digitalPinToPCMSKbit(p) ( (((p) >= 10) && ((p) <= 13)) ? ((p) - 6) : \
( ((p) == 14) ? 2 : \
( ((p) == 15) ? 1 : \
( ((p) == 50) ? 3 : \
( ((p) == 51) ? 2 : \
( ((p) == 52) ? 1 : \
( ((p) == 53) ? 0 : \
( (((p) >= 62) && ((p) <= 69)) ? ((p) - 62) : \
0 ) ) ) ) ) ) ) )
#endif
volatile uint8_t e_hit = 0; // Different from 0 when the endstops shall be tested in detail.
// Must be reset to 0 by the test function when the tests are finished.
// Install Pin change interrupt for a pin. Can be called multiple times.
void pciSetup(byte pin) {
*digitalPinToPCMSK(pin) |= bit (digitalPinToPCMSKbit(pin)); // enable pin
PCIFR |= bit (digitalPinToPCICRbit(pin)); // clear any outstanding interrupt
PCICR |= bit (digitalPinToPCICRbit(pin)); // enable interrupt for the group
}
// This is what is really done inside the interrupts.
FORCE_INLINE void endstop_ISR_worker( void ) {
e_hit = 2; // Because the detection of a e-stop hit has a 1 step debouncer it has to be called at least twice.
}
// Use one Routine to handle each group
// One ISR for all EXT-Interrupts
void endstop_ISR(void) { endstop_ISR_worker(); }
// Handlers for pin change interrupts
#ifdef PCINT0_vect
ISR(PCINT0_vect) { endstop_ISR_worker(); }
#endif
#ifdef PCINT1_vect
ISR(PCINT1_vect) { endstop_ISR_worker(); }
#endif
#ifdef PCINT2_vect
ISR(PCINT2_vect) { endstop_ISR_worker(); }
#endif
#ifdef PCINT3_vect
ISR(PCINT3_vect) { endstop_ISR_worker(); }
#endif
void setup_endstop_interrupts( void ) {
#if HAS_X_MAX
#if (digitalPinToInterrupt(X_MAX_PIN) != NOT_AN_INTERRUPT) // if pin has an external interrupt
attachInterrupt(digitalPinToInterrupt(X_MAX_PIN), endstop_ISR, CHANGE); // assign it
#else
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
static_assert(digitalPinToPCICR(X_MAX_PIN) != NULL, "X_MAX_PIN is not interrupt-capable"); // if pin has no pin change interrupt - error
pciSetup(X_MAX_PIN); // assign it
#endif
#endif
#if HAS_X_MIN
#if (digitalPinToInterrupt(X_MIN_PIN) != NOT_AN_INTERRUPT)
attachInterrupt(digitalPinToInterrupt(X_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(X_MIN_PIN) != NULL, "X_MIN_PIN is not interrupt-capable");
pciSetup(X_MIN_PIN);
#endif
#endif
#if HAS_Y_MAX
#if (digitalPinToInterrupt(Y_MAX_PIN) != NOT_AN_INTERRUPT)
attachInterrupt(digitalPinToInterrupt(Y_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(Y_MAX_PIN) != NULL, "Y_MAX_PIN is not interrupt-capable");
pciSetup(Y_MAX_PIN);
#endif
#endif
#if HAS_Y_MIN
#if (digitalPinToInterrupt(Y_MIN_PIN) != NOT_AN_INTERRUPT)
attachInterrupt(digitalPinToInterrupt(Y_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(Y_MIN_PIN) != NULL, "Y_MIN_PIN is not interrupt-capable");
pciSetup(Y_MIN_PIN);
#endif
#endif
#if HAS_Z_MAX
#if (digitalPinToInterrupt(Z_MAX_PIN) != NOT_AN_INTERRUPT)
attachInterrupt(digitalPinToInterrupt(Z_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(Z_MAX_PIN) != NULL, "Z_MAX_PIN is not interrupt-capable");
pciSetup(Z_MAX_PIN);
#endif
#endif
#if HAS_Z_MIN
#if (digitalPinToInterrupt(Z_MIN_PIN) != NOT_AN_INTERRUPT)
attachInterrupt(digitalPinToInterrupt(Z_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(Z_MIN_PIN) != NULL, "Z_MIN_PIN is not interrupt-capable");
pciSetup(Z_MIN_PIN);
#endif
#endif
#if HAS_Z2_MAX
#if (digitalPinToInterrupt(Z2_MAX_PIN) != NOT_AN_INTERRUPT)
attachInterrupt(digitalPinToInterrupt(Z2_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(Z2_MAX_PIN) != NULL, "Z2_MAX_PIN is not interrupt-capable");
pciSetup(Z2_MAX_PIN);
#endif
#endif
#if HAS_Z2_MIN
#if (digitalPinToInterrupt(Z2_MIN_PIN) != NOT_AN_INTERRUPT)
attachInterrupt(digitalPinToInterrupt(Z2_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(Z2_MIN_PIN) != NULL, "Z2_MIN_PIN is not interrupt-capable");
pciSetup(Z2_MIN_PIN);
#endif
#endif
#if HAS_Z_MIN_PROBE_PIN
#if (digitalPinToInterrupt(Z_MIN_PROBE_PIN) != NOT_AN_INTERRUPT)
attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_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(Z_MIN_PROBE_PIN) != NULL, "Z_MIN_PROBE_PIN is not interrupt-capable");
pciSetup(Z_MIN_PROBE_PIN);
#endif
#endif
// If we arrive here without raising an assertion, each pin has either an EXT-interrupt or a PCI.
}
#endif //_ENDSTOP_INTERRUPTS_H_

View File

@@ -122,7 +122,7 @@ void Endstops::init() {
#endif
#endif
#if HAS_Z_MIN_PROBE_PIN && ENABLED(Z_MIN_PROBE_ENDSTOP) // Check for Z_MIN_PROBE_ENDSTOP so we don't pull a pin high unless it's to be used.
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
SET_INPUT(Z_MIN_PROBE_PIN);
#if ENABLED(ENDSTOPPULLUP_ZMIN_PROBE)
WRITE(Z_MIN_PROBE_PIN,HIGH);
@@ -201,6 +201,10 @@ void Endstops::M119() {
SERIAL_PROTOCOLPGM(MSG_Z_MIN);
SERIAL_PROTOCOLLN(((READ(Z_MIN_PIN)^Z_MIN_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
#endif
#if HAS_Z2_MIN
SERIAL_PROTOCOLPGM(MSG_Z2_MIN);
SERIAL_PROTOCOLLN(((READ(Z2_MIN_PIN)^Z2_MIN_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
#endif
#if HAS_Z_MAX
SERIAL_PROTOCOLPGM(MSG_Z_MAX);
SERIAL_PROTOCOLLN(((READ(Z_MAX_PIN)^Z_MAX_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
@@ -209,7 +213,7 @@ void Endstops::M119() {
SERIAL_PROTOCOLPGM(MSG_Z2_MAX);
SERIAL_PROTOCOLLN(((READ(Z2_MAX_PIN)^Z2_MAX_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
#endif
#if HAS_Z_MIN_PROBE_PIN
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
SERIAL_PROTOCOLPGM(MSG_Z_PROBE);
SERIAL_PROTOCOLLN(((READ(Z_MIN_PROBE_PIN)^Z_MIN_PROBE_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
#endif
@@ -218,10 +222,9 @@ void Endstops::M119() {
#if ENABLED(Z_DUAL_ENDSTOPS)
// Pass the result of the endstop test
void Endstops::test_dual_z_endstops(EndstopEnum es1, 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
if (stepper.current_block->steps[Z_AXIS] > 0) {
stepper.endstop_triggered(Z_AXIS);
if (z_test && stepper.current_block->steps[Z_AXIS] > 0) {
SBI(endstop_hit_bits, Z_MIN);
if (!stepper.performing_homing || (z_test == 0x3)) //if not performing home or if both endstops were trigged during homing...
stepper.kill_current_block();
@@ -233,25 +236,39 @@ void Endstops::M119() {
// Check endstops - Called from ISR!
void Endstops::update() {
#define _ENDSTOP(AXIS, MINMAX) AXIS ##_## MINMAX
#define _ENDSTOP_PIN(AXIS, MINMAX) AXIS ##_## MINMAX ##_PIN
#define _ENDSTOP_INVERTING(AXIS, MINMAX) AXIS ##_## MINMAX ##_ENDSTOP_INVERTING
#define _ENDSTOP_HIT(AXIS) SBI(endstop_hit_bits, _ENDSTOP(AXIS, MIN))
#define _ENDSTOP(AXIS, MINMAX) AXIS ##_## MINMAX
// UPDATE_ENDSTOP_BIT: set the current endstop bits for an endstop to its status
#define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT(current_endstop_bits, _ENDSTOP(AXIS, MINMAX), (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX)))
// COPY_BIT: copy the value of COPY_BIT to BIT in bits
#define COPY_BIT(bits, COPY_BIT, BIT) SET_BIT(bits, BIT, TEST(bits, COPY_BIT))
// COPY_BIT: copy the value of SRC_BIT to DST_BIT in DST
#define COPY_BIT(DST, SRC_BIT, DST_BIT) SET_BIT(DST, DST_BIT, TEST(DST, SRC_BIT))
#define UPDATE_ENDSTOP(AXIS,MINMAX) do { \
#define _UPDATE_ENDSTOP(AXIS,MINMAX,CODE) do { \
UPDATE_ENDSTOP_BIT(AXIS, MINMAX); \
if (TEST_ENDSTOP(_ENDSTOP(AXIS, MINMAX)) && stepper.current_block->steps[_AXIS(AXIS)] > 0) { \
_ENDSTOP_HIT(AXIS); \
stepper.endstop_triggered(_AXIS(AXIS)); \
CODE; \
} \
} while(0)
#if ENABLED(COREXY) || ENABLED(COREXZ)
#if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN) // If G38 command then check Z_MIN for every axis and every direction
#define UPDATE_ENDSTOP(AXIS,MINMAX) do { \
_UPDATE_ENDSTOP(AXIS,MINMAX,NOOP); \
if (G38_move) _UPDATE_ENDSTOP(Z, MIN, G38_endstop_hit = true); \
} while(0)
#else
#define UPDATE_ENDSTOP(AXIS,MINMAX) _UPDATE_ENDSTOP(AXIS,MINMAX,NOOP)
#endif
#if CORE_IS_XY || CORE_IS_XZ
// Head direction in -X axis for CoreXY and CoreXZ bots.
// If DeltaA == -DeltaB, the movement is only in Y or Z axis
if ((stepper.current_block->steps[CORE_AXIS_1] != stepper.current_block->steps[CORE_AXIS_2]) || (stepper.motor_direction(CORE_AXIS_1) == stepper.motor_direction(CORE_AXIS_2))) {
@@ -281,11 +298,11 @@ void Endstops::update() {
#endif
}
}
#if ENABLED(COREXY) || ENABLED(COREXZ)
#if CORE_IS_XY || CORE_IS_XZ
}
#endif
#if ENABLED(COREXY) || ENABLED(COREYZ)
#if CORE_IS_XY || CORE_IS_YZ
// Head direction in -Y axis for CoreXY / CoreYZ bots.
// If DeltaA == DeltaB, the movement is only in X or Y axis
if ((stepper.current_block->steps[CORE_AXIS_1] != stepper.current_block->steps[CORE_AXIS_2]) || (stepper.motor_direction(CORE_AXIS_1) != stepper.motor_direction(CORE_AXIS_2))) {
@@ -303,11 +320,11 @@ void Endstops::update() {
UPDATE_ENDSTOP(Y, MAX);
#endif
}
#if ENABLED(COREXY) || ENABLED(COREYZ)
#if CORE_IS_XY || CORE_IS_YZ
}
#endif
#if ENABLED(COREXZ) || ENABLED(COREYZ)
#if CORE_IS_XZ || CORE_IS_YZ
// Head direction in -Z axis for CoreXZ or CoreYZ bots.
// If DeltaA == DeltaB, the movement is only in X or Y axis
if ((stepper.current_block->steps[CORE_AXIS_1] != stepper.current_block->steps[CORE_AXIS_2]) || (stepper.motor_direction(CORE_AXIS_1) != stepper.motor_direction(CORE_AXIS_2))) {
@@ -315,7 +332,7 @@ void Endstops::update() {
#else
if (stepper.motor_direction(Z_AXIS))
#endif
{ // z -direction
{ // Z -direction. Gantry down, bed up.
#if HAS_Z_MIN
#if ENABLED(Z_DUAL_ENDSTOPS)
@@ -331,7 +348,7 @@ void Endstops::update() {
#else // !Z_DUAL_ENDSTOPS
#if HAS_BED_PROBE && 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);
#else
UPDATE_ENDSTOP(Z, MIN);
@@ -341,16 +358,18 @@ void Endstops::update() {
#endif // HAS_Z_MIN
#if HAS_BED_PROBE && ENABLED(Z_MIN_PROBE_ENDSTOP) && DISABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
// When closing the gap check the enabled probe
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
if (z_probe_enabled) {
UPDATE_ENDSTOP(Z, MIN_PROBE);
if (TEST_ENDSTOP(Z_MIN_PROBE)) SBI(endstop_hit_bits, Z_MIN_PROBE);
}
#endif
}
else { // z +direction
else { // Z +direction. Gantry up, bed down.
#if HAS_Z_MAX
// Check both Z dual endstops
#if ENABLED(Z_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Z, MAX);
@@ -362,14 +381,16 @@ void Endstops::update() {
test_dual_z_endstops(Z_MAX, Z2_MAX);
#else // !Z_DUAL_ENDSTOPS
// If this pin is not hijacked for the bed probe
// then it belongs to the Z endstop
#elif DISABLED(Z_MIN_PROBE_ENDSTOP) || Z_MAX_PIN != Z_MIN_PROBE_PIN
UPDATE_ENDSTOP(Z, MAX);
#endif // !Z_DUAL_ENDSTOPS
#endif // !Z_MIN_PROBE_PIN...
#endif // Z_MAX_PIN
}
#if ENABLED(COREXZ)
#if CORE_IS_XZ || CORE_IS_YZ
}
#endif

View File

@@ -86,7 +86,7 @@ class Endstops {
private:
#if ENABLED(Z_DUAL_ENDSTOPS)
static void test_dual_z_endstops(EndstopEnum es1, EndstopEnum es2);
static void test_dual_z_endstops(const EndstopEnum es1, const EndstopEnum es2);
#endif
};

View File

@@ -23,6 +23,8 @@
#ifndef __ENUM_H__
#define __ENUM_H__
#include "MarlinConfig.h"
/**
* Axis indices as enumerated constants
*
@@ -42,11 +44,13 @@ enum AxisEnum {
E_AXIS = 3,
X_HEAD = 4,
Y_HEAD = 5,
Z_HEAD = 6
Z_HEAD = 6,
ALL_AXES = 100
};
#define LOOP_XYZ(VAR) for (uint8_t VAR=X_AXIS; VAR<=Z_AXIS; VAR++)
#define LOOP_XYZE(VAR) for (uint8_t VAR=X_AXIS; VAR<=E_AXIS; VAR++)
#define LOOP_XYZE_N(VAR) for (uint8_t VAR=X_AXIS; VAR<XYZE_N; VAR++)
typedef enum {
LINEARUNIT_MM,
@@ -70,7 +74,8 @@ enum DebugFlags {
DEBUG_ERRORS = _BV(2), ///< Not implemented
DEBUG_DRYRUN = _BV(3), ///< Ignore temperature setting and E movement commands
DEBUG_COMMUNICATION = _BV(4), ///< Not implemented
DEBUG_LEVELING = _BV(5) ///< Print detailed output for homing and leveling
DEBUG_LEVELING = _BV(5), ///< Print detailed output for homing and leveling
DEBUG_ALL = 0xFF
};
enum EndstopEnum {
@@ -190,4 +195,12 @@ enum LCDViewAction {
LCDVIEW_CALL_NO_REDRAW
};
#if ENABLED(DUAL_X_CARRIAGE)
enum DualXMode {
DXC_FULL_CONTROL_MODE,
DXC_AUTO_PARK_MODE,
DXC_DUPLICATION_MODE
};
#endif
#endif // __ENUM_H__

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(MaukCC, CartesioE)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 115200
// Enable the Bluetooth serial interface on AT90USB devices
@@ -134,9 +143,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 3
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -170,69 +182,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 -1
#define TEMP_SENSOR_1 -1
#define TEMP_SENSOR_2 1
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 1
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -282,7 +311,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -330,8 +358,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//24V 500W silicone heater on to 4mm glass CartesioW
#define DEFAULT_bedKp 390
#define DEFAULT_bedKi 70
@@ -347,14 +373,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MINTEMP 18
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -382,9 +411,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -428,16 +461,84 @@
#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 71.128, 71.128, 640, 152 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 200, 200, 20, 20 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 1000, 1000, 100, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 500 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 10000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 10.0
#define DEFAULT_YJERK 10.0
#define DEFAULT_ZJERK 0.4
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -449,6 +550,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -493,9 +595,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -513,16 +612,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -531,20 +638,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -553,7 +665,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 1
#define Y_ENABLE_ON 1
#define Z_ENABLE_ON 1
@@ -594,7 +706,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -616,11 +728,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -645,71 +757,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -742,27 +876,6 @@
#define HOMING_FEEDRATE_XY (50*60)
#define HOMING_FEEDRATE_Z (10*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {71.128,71.128,640,152}
#define DEFAULT_MAX_FEEDRATE {200,200,20,20} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {1000,1000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 500 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 10000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 10.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -932,9 +1045,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -958,7 +1071,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1270,6 +1383,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN 7
#define EXTRUDER_1_AUTO_FAN_PIN 7
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
//#define E0_AUTO_FAN_PIN -1
//#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 35
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -405,6 +422,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -446,15 +466,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -483,6 +507,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -499,9 +553,20 @@
#define D_FILAMENT 2.85
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -530,7 +595,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -546,7 +622,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -563,7 +639,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -641,126 +717,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -773,27 +1059,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -133,9 +142,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -169,69 +181,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 1
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -281,7 +310,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define K1 0.95 //smoothing factor within the PID
// Felix 2.0+ electronics with v4 Hotend
@@ -317,8 +345,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
// Felix Foil Heater
#define DEFAULT_bedKp 103.37
#define DEFAULT_bedKi 2.79
@@ -329,14 +355,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -364,9 +393,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -410,16 +443,85 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
// default steps per unit for Felix 2.0/3.0: 0.00249mm x/y rounding error with 3mm pitch HTD belt and 14 tooth pulleys. 0 z error.
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 76.190476, 76.190476, 1600, 164 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 500, 500, 5, 25 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 5000, 5000, 100, 80000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 1750 // X, Y, Z and E max acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 5000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 10.0
#define DEFAULT_YJERK 10.0
#define DEFAULT_ZJERK 0.3
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -431,6 +533,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -475,9 +578,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -495,16 +595,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -513,20 +621,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -535,7 +648,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -576,7 +689,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -598,11 +711,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -627,71 +740,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 180
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 180
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -724,28 +859,6 @@
#define HOMING_FEEDRATE_XY (50*60)
#define HOMING_FEEDRATE_Z (4*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
// default steps per unit for Felix 2.0/3.0: 0.00249mm x/y rounding error with 3mm pitch HTD belt and 14 tooth pulleys. 0 z error.
#define DEFAULT_AXIS_STEPS_PER_UNIT {76.190476, 76.190476, 1600, 164}
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {5000,5000,100,80000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 1750 //1500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 5000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 10 // (mm/sec)
#define DEFAULT_ZJERK 0.3 //0.4 // (mm/sec)
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -773,8 +886,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -915,9 +1028,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
//#define LCD_LANGUAGE en
@@ -941,7 +1054,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1253,6 +1366,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -405,6 +422,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -446,15 +466,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -483,6 +507,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -499,9 +553,20 @@
#define D_FILAMENT 2.85
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -530,7 +595,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -546,7 +622,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -563,7 +639,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -641,126 +717,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -773,27 +1059,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -133,9 +142,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 2
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -169,69 +181,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 1
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 1
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -281,7 +310,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define K1 0.95 //smoothing factor within the PID
// Felix 2.0+ electronics with v4 Hotend
@@ -327,14 +355,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -362,9 +393,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -408,16 +443,85 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
// default steps per unit for Felix 2.0/3.0: 0.00249mm x/y rounding error with 3mm pitch HTD belt and 14 tooth pulleys. 0 z error.
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 76.190476, 76.190476, 1600, 164 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 500, 500, 5, 25 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 5000, 5000, 100, 80000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 1750 // X, Y, Z and E max acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 5000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 10.0
#define DEFAULT_YJERK 10.0
#define DEFAULT_ZJERK 0.3
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -429,6 +533,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -473,9 +578,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -493,16 +595,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -511,20 +621,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -533,7 +648,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -574,7 +689,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -596,11 +711,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -625,71 +740,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 180
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 180
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -722,28 +859,6 @@
#define HOMING_FEEDRATE_XY (50*60)
#define HOMING_FEEDRATE_Z (4*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
// default steps per unit for Felix 2.0/3.0: 0.00249mm x/y rounding error with 3mm pitch HTD belt and 14 tooth pulleys. 0 z error.
#define DEFAULT_AXIS_STEPS_PER_UNIT {76.190476, 76.190476, 1600, 164}
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {5000,5000,100,80000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 1750 //1500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 5000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 10 // (mm/sec)
#define DEFAULT_ZJERK 0.3 //0.4 // (mm/sec)
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -913,9 +1028,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
//#define LCD_LANGUAGE en
@@ -939,7 +1054,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1251,6 +1366,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 115200
// Enable the Bluetooth serial interface on AT90USB devices
@@ -136,9 +145,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -172,69 +184,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 0
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -284,7 +313,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define K1 0.95 //smoothing factor within the PID
// Hephestos i3
@@ -320,8 +348,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
@@ -339,14 +365,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -374,9 +403,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -420,16 +453,84 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 4000, 100.47095761381482 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 200, 200, 3.3, 25 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 1100, 1100, 100, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 650 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 1000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 10.0
#define DEFAULT_YJERK 10.0
#define DEFAULT_ZJERK 0.4
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -441,6 +542,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -485,9 +587,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -505,38 +604,51 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_ENDSTOP
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
// The Z_MIN_PIN will then be used for both Z-homing and probing.
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
//#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -545,7 +657,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -586,7 +698,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -608,11 +720,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -637,71 +749,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -734,27 +868,6 @@
#define HOMING_FEEDRATE_XY 2000
#define HOMING_FEEDRATE_Z 150
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {80,80,4000,100.47095761381482} // default steps per unit for Ultimaker
#define DEFAULT_MAX_FEEDRATE {250, 250, 3.3, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {3000,3000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 1000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 10.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -782,8 +895,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -924,9 +1037,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
//#define LCD_LANGUAGE en
@@ -950,7 +1063,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1262,6 +1375,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -405,6 +422,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -446,15 +466,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -483,6 +507,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -499,9 +553,20 @@
#define D_FILAMENT 1.75
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -530,7 +595,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -546,7 +622,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -563,7 +639,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -641,126 +717,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -773,27 +1059,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "@jbrazio" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -133,9 +142,12 @@
#define MACHINE_UUID "8d083632-40c5-4649-85b8-43d9ae6c5d55" // BQ Hephestos 2 standard config
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -169,69 +181,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 70
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 0
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -281,7 +310,6 @@
// Set/get with gcode: M301 E[extruder number, 0-2]
#define PID_FUNCTIONAL_RANGE 250 // 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.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define K1 0.95 //smoothing factor within the PID
// Tuned PID values using M303
@@ -322,8 +350,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
@@ -341,14 +367,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -376,9 +405,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -422,16 +455,84 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 160, 160, 8000, 210.02 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 250, 250, 2, 200 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 1000, 1000, 20, 1000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 20.0
#define DEFAULT_YJERK 20.0
#define DEFAULT_ZJERK 0.4
#define DEFAULT_EJERK 2.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -443,6 +544,7 @@
#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -487,9 +589,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -507,38 +606,51 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_ENDSTOP
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
// The Z_MIN_PIN will then be used for both Z-homing and probing.
#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
//#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 5 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 2 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 5 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 2 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -547,7 +659,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 0
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -588,7 +700,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -610,11 +722,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -639,71 +751,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER
#define RIGHT_PROBE_BED_POSITION X_MAX_POS - (X_PROBE_OFFSET_FROM_EXTRUDER)
#define FRONT_PROBE_BED_POSITION Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER
#define BACK_PROBE_BED_POSITION Y_MAX_POS - (Y_PROBE_OFFSET_FROM_EXTRUDER)
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER
#define RIGHT_PROBE_BED_POSITION X_MAX_POS - (X_PROBE_OFFSET_FROM_EXTRUDER)
#define FRONT_PROBE_BED_POSITION Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER
#define BACK_PROBE_BED_POSITION Y_MAX_POS - (Y_PROBE_OFFSET_FROM_EXTRUDER)
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER
#define ABL_PROBE_PT_1_Y Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER
#define ABL_PROBE_PT_2_X X_MAX_POS - (X_PROBE_OFFSET_FROM_EXTRUDER)
#define ABL_PROBE_PT_2_Y Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER
#define ABL_PROBE_PT_3_X ((X_MIN_POS + X_MAX_POS) / 2)
#define ABL_PROBE_PT_3_Y Y_MAX_POS - (Y_PROBE_OFFSET_FROM_EXTRUDER)
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER
#define ABL_PROBE_PT_1_Y Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER
#define ABL_PROBE_PT_2_X X_MAX_POS - (X_PROBE_OFFSET_FROM_EXTRUDER)
#define ABL_PROBE_PT_2_Y Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER
#define ABL_PROBE_PT_3_X ((X_MIN_POS + X_MAX_POS) / 2)
#define ABL_PROBE_PT_3_Y Y_MAX_POS - (Y_PROBE_OFFSET_FROM_EXTRUDER)
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -736,27 +870,6 @@
#define HOMING_FEEDRATE_XY (150*60)
#define HOMING_FEEDRATE_Z 200
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {160, 160, 8000, 210.02} // Steps per unit
#define DEFAULT_MAX_FEEDRATE {250, 250, 2, 200} // mm/sec
#define DEFAULT_MAX_ACCELERATION {1000, 1000, 20, 1000} // X, Y, Z, E max start speed for accelerated moves
#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 20.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK 2.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -784,8 +897,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -926,9 +1039,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -952,7 +1065,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1264,6 +1377,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN 11
#define EXTRUDER_1_AUTO_FAN_PIN 6
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
//#define E0_AUTO_FAN_PIN -1
//#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -405,6 +422,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -446,15 +466,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -483,6 +507,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -499,9 +553,20 @@
#define D_FILAMENT 2.85
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -530,7 +595,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -546,7 +622,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -563,7 +639,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -641,126 +717,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -773,27 +1059,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -20,13 +20,6 @@
*
*/
/**
* Sample configuration file for Vellemann K8200
* tested on K8200 with VM8201 (Display)
* and Arduino 1.6.8 (Mac) by @CONSULitAS, 2016-02-21
* https://github.com/CONSULitAS/Marlin-K8200/archive/K8200_stable_2016-02-21.zip
*/
/**
* Configuration.h
*
@@ -58,6 +51,22 @@
*/
#define CONFIGURATION_H_VERSION 010100
/**
* Sample configuration file for Vellemann K8200
* tested on K8200 with VM8201 (Display)
* and Arduino 1.6.12 (Mac OS X) by @CONSULitAS, 2016-11-18
* https://github.com/CONSULitAS/Marlin-K8200/archive/K8200_stable_2016-11-18.zip
*
* Please choose your hardware options for the K8200:
*/
// VM8201 Display unit
#define K8200_VM8201
// K8204 Z axis upgrade rod and coupler -> TODO
// #define K8200_K8204
// K8203 direct drive extruder -> TODO
// #define K8200_K8203
//===========================================================================
//============================= Getting Started =============================
//===========================================================================
@@ -95,8 +104,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(K8200, @CONSULitAS)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -112,14 +121,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -137,12 +155,19 @@
// Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
// You can use an online service to generate a random UUID. (eg http://www.uuidgenerator.net/version4)
#define MACHINE_UUID "2b7dea3b-844e-4ab1-aa96-bb6406607d6e" // K8200 standard config with VM8201 (Display)
#if ENABLED(K8200_VM8201)
#define MACHINE_UUID "2b7dea3b-844e-4ab1-aa96-bb6406607d6e" // K8200 standard config with VM8201 (Display)
#else
#define MACHINE_UUID "92f72de1-c211-452e-9f2b-61ef88a4751e" // K8200 standard config without VM8201 (Display)
#endif
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -176,69 +201,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
#define POWER_SUPPLY 1
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 0
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 5
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -248,7 +290,7 @@
#define TEMP_WINDOW 1 // (degC) Window around target to start the residency timer x degC early.
// Bed temperature must be close to target for this long before M190 returns success
#define TEMP_BED_RESIDENCY_TIME 0 // (seconds)
#define TEMP_BED_RESIDENCY_TIME 10 // (seconds)
#define TEMP_BED_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one
#define TEMP_BED_WINDOW 1 // (degC) Window around target to start the residency timer x degC early.
@@ -288,7 +330,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -339,8 +380,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
//#define DEFAULT_bedKp 10.00
@@ -355,23 +394,26 @@
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
// Vellemann K8200 PCB heatbed with standard PCU at 60 degreesC - calculated with PID Autotune and tested
// from pidautotune
#define DEFAULT_bedKp 341.88
#define DEFAULT_bedKi 25.32
#define DEFAULT_bedKd 1153.89
// Vellemann K8200 PCB heatbed with standard PCU at 60 degreesC - calculated with PID Autotune and tested
// from pidautotune
#define DEFAULT_bedKp 341.88
#define DEFAULT_bedKi 25.32
#define DEFAULT_bedKd 1153.89
#endif // PIDTEMPBED
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -399,9 +441,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -440,21 +486,88 @@
#define X_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MIN_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define X_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define X_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 64.25, 64.25, 2560, 600 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 500, 500, 5, 25 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 9000, 9000, 100, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 1000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 20.0
#define DEFAULT_YJERK 20.0
#define DEFAULT_ZJERK 0.4
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -466,6 +579,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -493,9 +607,9 @@
// | |
// O-- FRONT --+
// (0,0)
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 // X offset: -left +right [of the nozzle]
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Y offset: -front +behind [the nozzle]
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z offset: -below +above [the nozzle]
#define X_PROBE_OFFSET_FROM_EXTRUDER 10 // X offset: -left +right [of the nozzle]
#define Y_PROBE_OFFSET_FROM_EXTRUDER 10 // Y offset: -front +behind [the nozzle]
#define Z_PROBE_OFFSET_FROM_EXTRUDER 0 // Z offset: -below +above [the nozzle]
// X and Y axis travel speed (mm/m) between probes
#define XY_PROBE_SPEED 8000
@@ -510,9 +624,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -530,16 +641,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -548,20 +667,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 10 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -570,7 +694,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -580,7 +704,7 @@
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z false // not for K8200 -> looses Steps
#define DISABLE_Z false
// Warn on display about possibly reduced accuracy
//#define DISABLE_REDUCED_ACCURACY_WARNING
@@ -593,7 +717,7 @@
// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
#define INVERT_X_DIR false
#define INVERT_Y_DIR false // was true -> why for K8200?
#define INVERT_Y_DIR false // K8200: false
#define INVERT_Z_DIR false
// @section extruder
@@ -605,13 +729,13 @@
#define INVERT_E3_DIR true
// @section homing
//#define Z_HOMING_HEIGHT 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
// Be sure you have this distance over your Z_MAX_POS in case.
// K8200: it is usual to have clamps for the glass plate on the heatbed
#define Z_HOMING_HEIGHT 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
// Be sure you have this distance over your Z_MAX_POS in case.
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -633,11 +757,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -662,71 +786,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -759,27 +905,6 @@
#define HOMING_FEEDRATE_XY (50*60)
#define HOMING_FEEDRATE_Z (4*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {64.25,64.25,2560,600} // default steps per unit for K8200
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 500} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 1000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 20.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -794,7 +919,7 @@
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
//define this to enable EEPROM support
#define EEPROM_SETTINGS
#define EEPROM_SETTINGS // K8200: uses EEPROM by default
#if ENABLED(EEPROM_SETTINGS)
// To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
@@ -807,8 +932,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -828,12 +953,12 @@
// @section temperature
// Preheat Constants
#define PREHEAT_1_TEMP_HOTEND 190
#define PREHEAT_1_TEMP_BED 50 // K8200: set back to 70 if you have an upgraded heatbed power supply
#define PREHEAT_1_TEMP_HOTEND 180
#define PREHEAT_1_TEMP_BED 50 // K8200: PLA / set back to 70 if you have an upgraded heatbed power supply
#define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255
#define PREHEAT_2_TEMP_HOTEND 240
#define PREHEAT_2_TEMP_BED 60 // K8200: set back to 110 if you have an upgraded heatbed power supply
#define PREHEAT_2_TEMP_BED 60 // K8200: ABS / set back to 110 if you have an upgraded heatbed power supply
#define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255
//
@@ -935,7 +1060,7 @@
// - Total time printing
//
// This information can be viewed by the M78 command.
//#define PRINTCOUNTER
#define PRINTCOUNTER
//=============================================================================
//============================= LCD and SD support ============================
@@ -943,15 +1068,18 @@
// @section lcd
// K8200: for Display VM8201 with SD slot
#if ENABLED(K8200_VM8201)
//
// LCD LANGUAGE
//
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -975,9 +1103,9 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE // K8200: for Display VM8201
#define DISPLAY_CHARSET_HD44780 JAPANESE // K8200: for Display VM8201 // this is the most common hardware
//
// LCD TYPE
@@ -1015,7 +1143,7 @@
//
// Use CRC checks and retries on the SD communication.
//
//#define SD_CHECK_AND_RETRY
#define SD_CHECK_AND_RETRY
//
// ENCODER SETTINGS
@@ -1023,13 +1151,13 @@
// This option overrides the default number of encoder pulses needed to
// produce one step. Should be increased for high-resolution encoders.
//
//#define ENCODER_PULSES_PER_STEP 1
#define ENCODER_PULSES_PER_STEP 4 // K8200_VM8201: four steps per encoder step
//
// Use this option to override the number of step signals required to
// move between next/prev menu items.
//
//#define ENCODER_STEPS_PER_MENU_ITEM 5
#define ENCODER_STEPS_PER_MENU_ITEM 1 // K8200_VM8201: One step per menu item
/**
* Encoder Direction Options
@@ -1054,14 +1182,14 @@
// If CLOCKWISE normally moves DOWN this makes it go UP.
// If CLOCKWISE normally moves UP this makes it go DOWN.
//
//#define REVERSE_MENU_DIRECTION
#define REVERSE_MENU_DIRECTION // K8200: for Display VM8201 encoder on right side
//
// Individual Axis Homing
//
// Add individual axis homing items (Home X, Home Y, and Home Z) to the LCD menu.
//
//#define INDIVIDUAL_AXIS_HOMING_MENU
#define INDIVIDUAL_AXIS_HOMING_MENU
//
// SPEAKER/BUZZER
@@ -1091,7 +1219,7 @@
//
// ULTIMAKER Controller.
//
//#define ULTIMAKERCONTROLLER
#define ULTIMAKERCONTROLLER // K8200: for Display VM8201
//
// ULTIPANEL as seen on Thingiverse.
@@ -1249,6 +1377,8 @@
//
//#define SAV_3DLCD
#endif // K8200_VM8201
//=============================================================================
//=============================== Extra Features ==============================
//=============================================================================
@@ -1287,6 +1417,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -20,12 +20,6 @@
*
*/
// Sample configuration file for Vellemann K8200
// tested on K8200 with VM8201 (Display)
// and Arduino 1.6.8 (Mac) by @CONSULitAS, 2016-02-21
// https://github.com/CONSULitAS/Marlin-K8200/archive/K8200_stable_2016-02-21.zip
/**
* Configuration_adv.h
*
@@ -36,6 +30,15 @@
* Basic settings can be found in Configuration.h
*
*/
/**
* Sample configuration file for Vellemann K8200
* tested on K8200 with VM8201 (Display)
* and Arduino 1.6.12 (Mac) by @CONSULitAS, 2016-11-18
* https://github.com/CONSULitAS/Marlin-K8200/archive/K8200_stable_2016-11-18.zip
*
*/
#ifndef CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H
@@ -80,6 +83,7 @@
* If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD
*/
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
// K8200 has weak heaters/power supply by default, so you have to relax!
#define THERMAL_PROTECTION_PERIOD 60 // Seconds
#define THERMAL_PROTECTION_HYSTERESIS 8 // Degrees Celsius
@@ -92,16 +96,19 @@
* If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE
* WATCH_TEMP_INCREASE should not be below 2.
*/
// K8200 has weak heaters/power supply by default, so you have to relax!
#define WATCH_TEMP_PERIOD 30 // Seconds
#define WATCH_TEMP_INCREASE 4 // Degrees Celsius
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
#endif
/**
* Thermal Protection parameters for the bed are just as above for hotends.
*/
#if ENABLED(THERMAL_PROTECTION_BED)
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
// K8200 has weak heaters/power supply by default, so you have to relax!
// the default bed is so weak, that you can hardly go over 75°C
#define THERMAL_PROTECTION_BED_PERIOD 60 // Seconds
#define THERMAL_PROTECTION_BED_HYSTERESIS 10 // Degrees Celsius
/**
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
@@ -174,14 +181,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -209,18 +218,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -306,7 +330,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -345,7 +369,7 @@
// Default stepper release if idle. Set to 0 to deactivate.
// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
// Time can be set by M18 and M84.
#define DEFAULT_STEPPER_DEACTIVE_TIME 60
#define DEFAULT_STEPPER_DEACTIVE_TIME 120
#define DISABLE_INACTIVE_X true
#define DISABLE_INACTIVE_Y true
#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished.
@@ -411,6 +435,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -452,15 +479,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -489,6 +520,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -505,13 +566,24 @@
#define D_FILAMENT 2.85
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
#define LIN_ADVANCE_K 75
#define LIN_ADVANCE_K 140 // start value for PLA on K8200
#endif
// @section leveling
@@ -536,7 +608,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 2; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -552,7 +635,7 @@ const unsigned int dropsegments = 2; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 32 // maximize block buffer
#endif
@@ -569,8 +652,8 @@ const unsigned int dropsegments = 2; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
#define TX_BUFFER_SIZE 0
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 128
// Enable an emergency-command parser to intercept certain commands as they
// enter the serial receive buffer, so they cannot be blocked.
@@ -609,9 +692,9 @@ const unsigned int dropsegments = 2; //everything with less than this number of
// Add support for experimental filament exchange support M600; requires display
#if ENABLED(ULTIPANEL)
// #define FILAMENT_CHANGE_FEATURE // Enable filament exchange menu and M600 g-code (used for runout sensor too)
#define FILAMENT_CHANGE_FEATURE // Enable filament exchange menu and M600 g-code (used for runout sensor too)
#if ENABLED(FILAMENT_CHANGE_FEATURE)
#define FILAMENT_CHANGE_X_POS 3 // X position of hotend
#define FILAMENT_CHANGE_X_POS (X_MAX_POS-3) // X position of hotend
#define FILAMENT_CHANGE_Y_POS 3 // Y position of hotend
#define FILAMENT_CHANGE_Z_ADD 10 // Z addition of hotend (lift)
#define FILAMENT_CHANGE_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis)
@@ -647,126 +730,336 @@ const unsigned int dropsegments = 2; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -779,27 +1072,43 @@ const unsigned int dropsegments = 2; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -7,7 +7,7 @@
* VM8201 uses "DISPLAY_CHARSET_HD44870_JAPAN" and "ULTIMAKERCONTROLLER"
* german (de) translation with umlaut is supported now - thanks to @AnHardt for the great hardware based umlaut support
I [@CONSULitAS](https://github.com/CONSULitAS) tested the changes on my K8200 with 20x4-LCD and Arduino 1.6.1 for Windows (SD library added to IDE manually) - everything works well.
I [@CONSULitAS](https://github.com/CONSULitAS) tested the changes on my K8200 with 20x4-LCD and Arduino 1.6.12 for Mac (SD library added to IDE manually), 2016-11-18 - everything works well.
**Source for genuine [Vellemann Firmware](http://www.k8200.eu/support/downloads/)**
* V2.1.1 (for z axis upgrade, date branched: 2013-06-05): [firmware_k8200_v2.1.1.zip](http://www.k8200.eu/downloads/files/downloads/firmware_k8200_v2.1.1.zip)

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(Anthony Birkett, default config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -133,9 +142,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -169,69 +181,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 0
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -281,7 +310,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -328,8 +356,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
@@ -347,14 +373,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MINTEMP 160
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -382,9 +411,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -428,16 +461,84 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 134.74, 134.74, 4266.66, 148.7 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 160, 160, 10, 10000 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 9000, 9000, 100, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 6000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 6000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 10.0
#define DEFAULT_YJERK 10.0
#define DEFAULT_ZJERK 0.5
#define DEFAULT_EJERK 20.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -449,6 +550,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -493,9 +595,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -513,16 +612,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -531,20 +638,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -553,7 +665,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -594,7 +706,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -616,11 +728,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -645,71 +757,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -742,27 +876,6 @@
#define HOMING_FEEDRATE_XY (50*60)
#define HOMING_FEEDRATE_Z (8*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {134.74,134.74,4266.66,148.7} // default steps per unit for Ultimaker
#define DEFAULT_MAX_FEEDRATE {160, 160, 10, 10000} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 6000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 6000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 10.0 // (mm/sec)
#define DEFAULT_ZJERK 0.5 // (mm/sec)
#define DEFAULT_EJERK 20.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -932,9 +1045,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -958,7 +1071,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1270,6 +1383,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -405,6 +422,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -446,15 +466,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -483,6 +507,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -499,9 +553,20 @@
#define D_FILAMENT 2.85
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -530,7 +595,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -546,7 +622,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -563,7 +639,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -641,126 +717,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -773,27 +1059,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(Anthony Birkett, default config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -133,9 +142,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 2
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -169,69 +181,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 5
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 0
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -281,7 +310,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -328,8 +356,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
@@ -347,14 +373,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MINTEMP 160
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -382,9 +411,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -428,16 +461,84 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 134.74, 134.74, 4266.66, 148.7 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 160, 160, 10, 10000 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 9000, 9000, 100, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 6000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 6000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 10.0
#define DEFAULT_YJERK 10.0
#define DEFAULT_ZJERK 0.5
#define DEFAULT_EJERK 20.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -449,6 +550,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -493,9 +595,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -513,16 +612,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -531,20 +638,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -553,7 +665,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -594,7 +706,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -616,11 +728,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -645,71 +757,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -742,27 +876,6 @@
#define HOMING_FEEDRATE_XY (50*60)
#define HOMING_FEEDRATE_Z (8*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {134.74,134.74,4266.66,148.7} // default steps per unit for Ultimaker
#define DEFAULT_MAX_FEEDRATE {160, 160, 10, 10000} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 6000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 6000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 10.0 // (mm/sec)
#define DEFAULT_ZJERK 0.5 // (mm/sec)
#define DEFAULT_EJERK 20.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -932,9 +1045,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -958,7 +1071,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1270,6 +1383,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "RepRapWorld.com" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -133,9 +142,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -169,69 +181,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 1
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -281,7 +310,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -328,8 +356,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
@@ -347,14 +373,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -382,9 +411,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -428,16 +461,84 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 78.7402*2, 78.7402*2, 5120.00, 760*1*1.5 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 20.0
#define DEFAULT_YJERK 20.0
#define DEFAULT_ZJERK 0.4
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -449,6 +550,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -493,9 +595,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -513,16 +612,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -531,20 +638,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -553,7 +665,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -594,7 +706,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -616,11 +728,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -645,71 +757,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -742,27 +876,6 @@
#define HOMING_FEEDRATE_XY (50*60)
#define HOMING_FEEDRATE_Z (4*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {78.7402*2,78.7402*2,5120.00,760*1*1.5} // default steps per unit for Ultimaker
#define DEFAULT_MAX_FEEDRATE {300, 300, 5, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {3000,3000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 20.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -790,8 +903,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -932,9 +1045,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -958,7 +1071,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1270,6 +1383,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 115200
// Enable the Bluetooth serial interface on AT90USB devices
@@ -136,9 +145,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1 // Single extruder. Set to 2 for dual extruders
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -172,69 +184,86 @@
#define HOTEND_OFFSET_X {0.0, 36.00} // (in mm) for each extruder, offset of the hotend on the X axis
#define HOTEND_OFFSET_Y {0.0, 0.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1 // DGlass3D = 5; RigidBot = 1; 3DSv6 = 5
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 1
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
//#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -284,7 +313,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -332,8 +360,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//RigidBot, from pid autotune
#define DEFAULT_bedKp 355
#define DEFAULT_bedKi 66.5
@@ -344,14 +370,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -379,9 +408,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -425,16 +458,86 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
// default steps per unit for RigidBot with standard hardware
#define DEFAULT_AXIS_STEPS_PER_UNIT { 44.3090, 22.1545, 1600, 53.5 }
// default steps for 16-tooth pulleys { 100.06, 50.06, 1600, 76 } // HPX2-MAX E=504, RigidBot E=53.5, Peter Stoneham's=76
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 500, 500, 5, 25 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 800, 800, 100, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 600 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 1000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 8.0
#define DEFAULT_YJERK 8.0
#define DEFAULT_ZJERK 0.4
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -446,6 +549,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -490,9 +594,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -510,16 +611,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -528,20 +637,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -550,7 +664,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -591,7 +705,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -613,11 +727,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -642,71 +756,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -739,28 +875,6 @@
#define HOMING_FEEDRATE_XY (50*60)
#define HOMING_FEEDRATE_Z (15*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {44.3090, 22.1545, 1600, 53.5} // default steps per unit for RigidBot with standard hardware
// default steps for 16-teth polleys {100.06,50.06,1600,76}, HPX2-MAX E=504, RigidBot E=53.5, Peter Stoneham's=76
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {800, 800, 100, 10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 600 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 1000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 8.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -788,8 +902,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -930,9 +1044,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -956,7 +1070,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1270,6 +1384,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -405,6 +422,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -446,15 +466,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -483,6 +507,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -499,9 +553,20 @@
#define D_FILAMENT 1.75
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -530,7 +595,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -546,7 +622,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -563,7 +639,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -641,126 +717,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -773,27 +1059,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -75,35 +75,42 @@
//
//===========================================================================
//========================= SCARA Settings ==================================
//============================= SCARA Printer ===============================
//===========================================================================
// SCARA-mode for Marlin has been developed by QHARLEY in ZA in 2012/2013. Implemented
// MORGAN_SCARA for Marlin was developed by QHARLEY in ZA in 2012/2013. Implemented
// and slightly reworked by JCERNY in 06/2014 with the goal to bring it into Master-Branch
// QHARLEYS Autobedlevelling has not been ported, because Marlin has now Bed-levelling
// You might need Z-Min endstop on SCARA-Printer to use this feature. Actually untested!
// Uncomment to use Morgan scara mode
#define SCARA
#define SCARA_SEGMENTS_PER_SECOND 200 // If movement is choppy try lowering this value
// Length of inner support arm
#define Linkage_1 150 //mm Preprocessor cannot handle decimal point...
// Length of outer support arm Measure arm lengths precisely and enter
#define Linkage_2 150 //mm
// SCARA tower offset (position of Tower relative to bed zero position)
// This needs to be reasonably accurate as it defines the printbed position in the SCARA space.
#define SCARA_offset_x 100 //mm
#define SCARA_offset_y -56 //mm
#define SCARA_RAD2DEG 57.2957795 // to convert RAD to degrees
// Specify the specific SCARA model
#define MORGAN_SCARA
//#define MAKERARM_SCARA
#define THETA_HOMING_OFFSET 0 //calculatated from Calibration Guide and command M360 / M114 see picture in http://reprap.harleystudio.co.za/?page_id=1073
#define PSI_HOMING_OFFSET 0 //calculatated from Calibration Guide and command M364 / M114 see picture in http://reprap.harleystudio.co.za/?page_id=1073
#if ENABLED(MORGAN_SCARA) || ENABLED(MAKERARM_SCARA)
//#define DEBUG_SCARA_KINEMATICS
//some helper variables to make kinematics faster
#define L1_2 sq(Linkage_1) // do not change
#define L2_2 sq(Linkage_2) // do not change
// If movement is choppy try lowering this value
#define SCARA_SEGMENTS_PER_SECOND 200
// Length of inner and outer support arms. Measure arm lengths precisely.
#define SCARA_LINKAGE_1 150 //mm
#define SCARA_LINKAGE_2 150 //mm
// SCARA tower offset (position of Tower relative to bed zero position)
// This needs to be reasonably accurate as it defines the printbed position in the SCARA space.
#define SCARA_OFFSET_X 100 //mm
#define SCARA_OFFSET_Y -56 //mm
// Radius around the center where the arm cannot reach
#define MIDDLE_DEAD_ZONE_R 0 //mm
#define THETA_HOMING_OFFSET 0 //calculatated from Calibration Guide and command M360 / M114 see picture in http://reprap.harleystudio.co.za/?page_id=1073
#define PSI_HOMING_OFFSET 0 //calculatated from Calibration Guide and command M364 / M114 see picture in http://reprap.harleystudio.co.za/?page_id=1073
#endif
//===========================================================================
//========================= SCARA Settings end ==============================
//==================== END ==== SCARA Printer ==== END ======================
//===========================================================================
// @section info
@@ -113,8 +120,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -130,14 +137,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -158,9 +174,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -194,69 +213,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 1
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -306,7 +342,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define K1 0.95 //smoothing factor within the PID
// Merlin Hotend: From Autotune
@@ -342,8 +377,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//12v Heatbed Mk3 12V in parallel
//from pidautotune
#define DEFAULT_bedKp 630.14
@@ -355,14 +388,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
//#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MINTEMP 150
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -390,9 +426,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -436,16 +476,84 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 103.69, 106.65, 200/1.25, 1000 } // default steps per unit for SCARA
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 300, 300, 30, 25 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 300, 300, 20, 1000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 400 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 2000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 400 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 5.0
#define DEFAULT_YJERK 5.0
#define DEFAULT_ZJERK 0.4
#define DEFAULT_EJERK 3.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -457,6 +565,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -501,9 +610,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -521,16 +627,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -539,20 +653,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -561,7 +680,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -602,7 +721,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR 1
#define Y_HOME_DIR 1
#define Z_HOME_DIR -1
@@ -624,11 +743,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -653,71 +772,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -750,27 +891,6 @@
#define HOMING_FEEDRATE_XY (40*60)
#define HOMING_FEEDRATE_Z (10*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {103.69,106.65,200/1.25,1000} // default steps per unit for SCARA
#define DEFAULT_MAX_FEEDRATE {300, 300, 30, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {300,300,20,1000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 400 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 2000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 400 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 5 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK 3 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -798,8 +918,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -940,9 +1060,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
//#define LCD_LANGUAGE en
@@ -966,7 +1086,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1278,6 +1398,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 180
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 180 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 180 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -405,6 +422,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -446,15 +466,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -483,6 +507,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -499,9 +553,20 @@
#define D_FILAMENT 1.75
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -530,7 +595,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -546,7 +622,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -563,7 +639,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -641,126 +717,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -773,27 +1059,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(Aleph Objects, Inc, TAZ config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -133,9 +142,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -169,69 +181,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 7
#define TEMP_SENSOR_1 7
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 7
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -281,7 +310,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -338,8 +366,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//24V 360W silicone heater from NPH on 3mm borosilicate (TAZ 2.2+)
#define DEFAULT_bedKp 20
#define DEFAULT_bedKi 5
@@ -368,14 +394,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -403,9 +432,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -449,16 +482,84 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 100.5, 100.5, 400, 850 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 800, 800, 8, 50 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 9000, 9000, 100, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 500 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 8.0
#define DEFAULT_YJERK 8.0
#define DEFAULT_ZJERK 0.4
#define DEFAULT_EJERK 10.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -470,6 +571,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -514,9 +616,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -534,16 +633,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -552,20 +659,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -574,7 +686,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -615,7 +727,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -637,11 +749,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -666,71 +778,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -763,27 +897,6 @@
#define HOMING_FEEDRATE_XY (50*60)
#define HOMING_FEEDRATE_Z (8*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {100.5,100.5,400,850} // default steps per unit for Ultimaker
#define DEFAULT_MAX_FEEDRATE {800, 800, 8, 50} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 500 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 8.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK 10.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -811,8 +924,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -953,9 +1066,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -979,7 +1092,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1291,6 +1404,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -211,18 +213,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -308,7 +325,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -413,6 +430,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -454,15 +474,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -491,6 +515,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -507,9 +561,20 @@
#define D_FILAMENT 2.85
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -538,7 +603,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -554,7 +630,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -571,7 +647,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -649,126 +725,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -781,27 +1067,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(bq Witbox)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 115200
// Enable the Bluetooth serial interface on AT90USB devices
@@ -136,9 +145,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -172,69 +184,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 0
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -284,7 +313,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define K1 0.95 //smoothing factor within the PID
// Witbox
@@ -320,8 +348,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
@@ -339,14 +365,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -374,9 +403,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -420,16 +453,84 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 600.0*8/3, 102.073 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 350, 350, 7.2, 80 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 1000, 1000, 10, 1000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 10.0
#define DEFAULT_YJERK 10.0
#define DEFAULT_ZJERK 0.4
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -441,6 +542,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -485,9 +587,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -505,16 +604,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -523,20 +630,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -545,7 +657,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -586,7 +698,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR 1
#define Y_HOME_DIR 1
#define Z_HOME_DIR -1
@@ -608,11 +720,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -637,71 +749,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -734,27 +868,6 @@
#define HOMING_FEEDRATE_XY (120*60)
#define HOMING_FEEDRATE_Z 432
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {80,80,600.0*8/3,102.073} // default steps per unit for Ultimaker
#define DEFAULT_MAX_FEEDRATE {350, 350, 7.2, 80} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {1000,1000,10,1000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 10.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -782,8 +895,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -924,9 +1037,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
//#define LCD_LANGUAGE en
@@ -950,7 +1063,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1262,6 +1375,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -405,6 +422,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -446,15 +466,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -483,6 +507,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -499,9 +553,20 @@
#define D_FILAMENT 1.75
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -530,7 +595,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -546,7 +622,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -563,7 +639,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -641,126 +717,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -773,27 +1059,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -133,9 +142,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -169,69 +181,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 0
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -281,7 +310,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -328,8 +356,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
@@ -347,14 +373,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -382,9 +411,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -428,16 +461,84 @@
#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 4000, 500 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 20.0
#define DEFAULT_YJERK 20.0
#define DEFAULT_ZJERK 0.4
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -449,6 +550,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -493,9 +595,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -513,16 +612,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -531,20 +638,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -553,7 +665,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -594,7 +706,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -616,11 +728,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -645,71 +757,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -742,27 +876,6 @@
#define HOMING_FEEDRATE_XY (50*60)
#define HOMING_FEEDRATE_Z (4*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {80,80,4000,500} // default steps per unit for Ultimaker
#define DEFAULT_MAX_FEEDRATE {300, 300, 5, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {3000,3000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 20.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -790,8 +903,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -932,9 +1045,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -958,7 +1071,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1270,6 +1383,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -133,9 +142,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 2
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -169,69 +181,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 5
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 1
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -281,7 +310,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -328,8 +356,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
@@ -347,14 +373,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -382,9 +411,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
//===========================================================================
//============================== Delta Settings =============================
@@ -426,6 +459,11 @@
// in ultralcd.cpp@lcd_delta_calibrate_menu()
//#define DELTA_CALIBRATION_MENU
// After homing move down to a height where XY movement is unconstrained
#define DELTA_HOME_TO_SAFE_ZONE
//#define DELTA_ENDSTOP_ADJ { 0, 0, 0 }
#endif
// Enable this option for Toshiba steppers
@@ -470,16 +508,85 @@
#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
// delta speeds must be the same on xyz
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 72.9, 72.9, 72.9, 291 } // default steps per unit for BI v2.5 (cable drive)
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 500, 500, 500, 150 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 9000, 9000, 9000, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 15.0
#define DEFAULT_YJERK 15.0
#define DEFAULT_ZJERK 15.0 // Must be same as XY for delta
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -491,6 +598,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -550,16 +658,16 @@
#define Z_PROBE_ALLEN_KEY_DEPLOY_2_Z 100.0
#define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE XY_PROBE_SPEED
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_X Z_PROBE_ALLEN_KEY_DEPLOY_2_X * 0.75
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_Y Z_PROBE_ALLEN_KEY_DEPLOY_2_Y * 0.75
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_Z Z_PROBE_ALLEN_KEY_DEPLOY_2_Z
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE XY_PROBE_SPEED
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_X 45.00 // Move right to trigger deploy pin
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_Y -125.00
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_Z 100.0
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE (XY_PROBE_SPEED)/2
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_X Z_PROBE_ALLEN_KEY_DEPLOY_3_X * 0.75
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_Y Z_PROBE_ALLEN_KEY_DEPLOY_3_Y * 0.75
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_Z Z_PROBE_ALLEN_KEY_DEPLOY_3_Z
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE XY_PROBE_SPEED
#define Z_PROBE_ALLEN_KEY_STOW_1_X 36.00 // Line up with bed retaining clip
#define Z_PROBE_ALLEN_KEY_STOW_1_Y -122.00
#define Z_PROBE_ALLEN_KEY_STOW_1_Z 75.0
@@ -582,9 +690,6 @@
#endif // Z_PROBE_ALLEN_KEY
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -602,16 +707,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -620,20 +733,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 50 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 50 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -642,7 +760,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -683,7 +801,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR 1 // deltas always home to max
#define Y_HOME_DIR 1
#define Z_HOME_DIR 1
@@ -705,11 +823,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -734,75 +852,95 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
// Works best with 5 or more points in each dimension.
#define ABL_GRID_POINTS_X 9
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID // Deltas only support grid mode.
// Set the boundaries for probing (where the probe can reach).
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
#define LEFT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
#define FRONT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define BACK_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
// Set the rectangle in which to probe.
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
#define LEFT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
#define FRONT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define BACK_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Non-linear bed leveling will be used.
// Compensate by interpolating between the nearest four Z probe values for each point.
// Useful for deltas where the print surface may appear like a bowl or dome shape.
// Works best with AUTO_BED_LEVELING_GRID_POINTS 5 or higher.
#define AUTO_BED_LEVELING_GRID_POINTS 9
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -831,31 +969,9 @@
#define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28).
#endif
// Delta only homes to Z
#define HOMING_FEEDRATE_Z (200*30)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
// delta speeds must be the same on xyz
#define DEFAULT_AXIS_STEPS_PER_UNIT {72.9, 72.9, 72.9, 291} // default steps per unit for BI v2.5 (cable drive)
#define DEFAULT_MAX_FEEDRATE {500, 500, 500, 150} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,9000,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 15.0 // (mm/sec)
#define DEFAULT_ZJERK 15.0 // (mm/sec) Must be same as XY for delta
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -883,8 +999,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -1025,9 +1141,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -1051,7 +1167,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1363,6 +1479,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -407,6 +424,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -448,15 +468,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -485,6 +509,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -501,9 +555,20 @@
#define D_FILAMENT 2.85
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -532,7 +597,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -548,7 +624,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -565,7 +641,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -643,126 +719,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -775,27 +1061,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -133,9 +142,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -169,69 +181,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 -1
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 0
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -281,7 +310,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -328,8 +356,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
@@ -347,14 +373,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -382,9 +411,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
//===========================================================================
//============================== Delta Settings =============================
@@ -426,6 +459,11 @@
// in ultralcd.cpp@lcd_delta_calibrate_menu()
//#define DELTA_CALIBRATION_MENU
// After homing move down to a height where XY movement is unconstrained
#define DELTA_HOME_TO_SAFE_ZONE
//#define DELTA_ENDSTOP_ADJ { 0, 0, 0 }
#endif
// Enable this option for Toshiba steppers
@@ -470,16 +508,85 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
// delta speeds must be the same on xyz
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 80, 760*1.1 } // default steps per unit for Kossel (GT2, 20 tooth)
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 500, 500, 500, 25 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 9000, 9000, 9000, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 20.0
#define DEFAULT_YJERK 20.0
#define DEFAULT_ZJERK 20.0 // Must be same as XY for delta
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -491,6 +598,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -576,9 +684,6 @@
#endif // Z_PROBE_ALLEN_KEY
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -596,16 +701,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -614,20 +727,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -636,7 +754,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -677,7 +795,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR 1 // deltas always home to max
#define Y_HOME_DIR 1
#define Z_HOME_DIR 1
@@ -699,11 +817,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -728,75 +846,95 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
// Works best with 5 or more points in each dimension.
#define ABL_GRID_POINTS_X 9
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID // Deltas only support grid mode.
// Set the boundaries for probing (where the probe can reach).
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
#define LEFT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
#define FRONT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define BACK_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
// Set the rectangle in which to probe
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
#define LEFT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
#define FRONT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define BACK_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Non-linear bed leveling will be used.
// Compensate by interpolating between the nearest four Z probe values for each point.
// Useful for deltas where the print surface may appear like a bowl or dome shape.
// Works best with AUTO_BED_LEVELING_GRID_POINTS 5 or higher.
#define AUTO_BED_LEVELING_GRID_POINTS 9
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -825,31 +963,9 @@
#define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28).
#endif
// Delta only homes to Z
#define HOMING_FEEDRATE_Z (200*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
// delta speeds must be the same on xyz
#define DEFAULT_AXIS_STEPS_PER_UNIT {80, 80, 80, 760*1.1} // default steps per unit for Kossel (GT2, 20 tooth)
#define DEFAULT_MAX_FEEDRATE {500, 500, 500, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,9000,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 20.0 // (mm/sec)
#define DEFAULT_ZJERK 20.0 // (mm/sec) Must be same as XY for delta
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -877,8 +993,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -1019,9 +1135,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -1045,7 +1161,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1357,6 +1473,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -407,6 +424,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -448,15 +468,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -485,6 +509,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -501,9 +555,20 @@
#define D_FILAMENT 2.85
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -532,7 +597,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -548,7 +624,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -565,7 +641,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -643,126 +719,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -775,27 +1061,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -133,9 +142,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -169,69 +181,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 7
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 11
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 5
@@ -281,7 +310,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -328,8 +356,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
@@ -347,14 +373,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -382,9 +411,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
//===========================================================================
//============================== Delta Settings =============================
@@ -426,6 +459,11 @@
// in ultralcd.cpp@lcd_delta_calibrate_menu()
//#define DELTA_CALIBRATION_MENU
// After homing move down to a height where XY movement is unconstrained
#define DELTA_HOME_TO_SAFE_ZONE
//#define DELTA_ENDSTOP_ADJ { 0, 0, 0 }
#endif
// Enable this option for Toshiba steppers
@@ -470,16 +508,85 @@
#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
// delta speeds must be the same on xyz
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 80, 760*1.1 } // default steps per unit for Kossel (GT2, 20 tooth)
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 500, 500, 500, 25 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 9000, 9000, 9000, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 20.0
#define DEFAULT_YJERK 20.0
#define DEFAULT_ZJERK 20.0 // Must be same as XY for delta
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -491,6 +598,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -579,9 +687,6 @@
#endif // Z_PROBE_ALLEN_KEY
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -599,16 +704,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -617,20 +730,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 50 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 50 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -639,7 +757,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -680,7 +798,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR 1 // deltas always home to max
#define Y_HOME_DIR 1
#define Z_HOME_DIR 1
@@ -702,11 +820,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -731,75 +849,95 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
// Works best with 5 or more points in each dimension.
#define ABL_GRID_POINTS_X 9
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID // Deltas only support grid mode.
// Set the boundaries for probing (where the probe can reach).
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
#define LEFT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
#define FRONT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define BACK_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
// Set the rectangle in which to probe
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
#define LEFT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
#define FRONT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define BACK_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Non-linear bed leveling will be used.
// Compensate by interpolating between the nearest four Z probe values for each point.
// Useful for deltas where the print surface may appear like a bowl or dome shape.
// Works best with AUTO_BED_LEVELING_GRID_POINTS 5 or higher.
#define AUTO_BED_LEVELING_GRID_POINTS 9
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -828,31 +966,9 @@
#define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28).
#endif
// Delta only homes to Z
#define HOMING_FEEDRATE_Z (200*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
// delta speeds must be the same on xyz
#define DEFAULT_AXIS_STEPS_PER_UNIT {80, 80, 80, 760*1.1} // default steps per unit for Kossel (GT2, 20 tooth)
#define DEFAULT_MAX_FEEDRATE {500, 500, 500, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,9000,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 20.0 // (mm/sec)
#define DEFAULT_ZJERK 20.0 // (mm/sec) Must be same as XY for delta
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -880,8 +996,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -1022,9 +1138,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -1048,7 +1164,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1360,6 +1476,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -362,6 +379,7 @@
#define DEFAULT_MINSEGMENTTIME 20000
// If defined the movements slow down when the look ahead buffer is only half full
// (don't use SLOWDOWN with DELTA because DELTA generates hundreds of segments per second)
//#define SLOWDOWN
// Frequency limit
@@ -406,6 +424,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -447,15 +468,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -484,6 +509,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -500,9 +555,20 @@
#define D_FILAMENT 2.85
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -531,7 +597,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -547,7 +624,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -564,7 +641,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -642,126 +719,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -774,27 +1061,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -22,8 +22,6 @@
/**
* Example configuration file for OpenBeam Kossel Pro
* tested on 2015-05-19 by @Wackerbarth
* using Arduino 1.6.5 (Mac)
*/
/**
@@ -94,8 +92,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -111,14 +109,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 115200
// Enable the Bluetooth serial interface on AT90USB devices
@@ -139,9 +146,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -175,69 +185,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 5
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -287,7 +314,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define K1 0.95 //smoothing factor within the PID
// Kossel Pro
@@ -323,8 +349,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//Kossel Pro heated bed plate with borosilicate glass
//from pidautotune (M303 E-1 S60 C8)
#define DEFAULT_bedKp 370.25
@@ -336,14 +360,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -371,9 +398,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
//===========================================================================
//============================== Delta Settings =============================
@@ -415,6 +446,11 @@
// in ultralcd.cpp@lcd_delta_calibrate_menu()
//#define DELTA_CALIBRATION_MENU
// After homing move down to a height where XY movement is unconstrained
#define DELTA_HOME_TO_SAFE_ZONE
//#define DELTA_ENDSTOP_ADJ { 0, 0, 0 }
#endif
// Enable this option for Toshiba steppers
@@ -459,16 +495,92 @@
#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
#define XYZ_FULL_STEPS_PER_ROTATION 200
#define XYZ_MICROSTEPS 32
#define XYZ_BELT_PITCH 2
#define XYZ_PULLEY_TEETH 20
// delta speeds must be the same on xyz
#define XYZ_STEPS ((XYZ_FULL_STEPS_PER_ROTATION) * (XYZ_MICROSTEPS) / double(XYZ_BELT_PITCH) / double(XYZ_PULLEY_TEETH))
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { XYZ_STEPS, XYZ_STEPS, XYZ_STEPS, 184.8 }
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 200, 200, 200, 200 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 9000, 9000, 9000, 9000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 20.0
#define DEFAULT_YJERK 20.0
#define DEFAULT_ZJERK 20.0 // Must be same as XY for delta
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -480,6 +592,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -546,10 +659,10 @@
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_Z Z_PROBE_ALLEN_KEY_DEPLOY_2_Z
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE XY_PROBE_SPEED
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_X 45.00 // Move right to trigger deploy pin
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_Y -125.00
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_Z Z_PROBE_ALLEN_KEY_DEPLOY_2_Z
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE (XY_PROBE_SPEED)/2
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_X 45.00 // Move right to trigger deploy pin
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_Y -125.00
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_Z Z_PROBE_ALLEN_KEY_DEPLOY_3_Z
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE (XY_PROBE_SPEED)/2
#define Z_PROBE_ALLEN_KEY_STOW_1_X 36.00 // Line up with bed retaining clip
#define Z_PROBE_ALLEN_KEY_STOW_1_Y -125.00
@@ -573,9 +686,6 @@
#endif // Z_PROBE_ALLEN_KEY
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -593,16 +703,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -611,20 +729,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 100 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 100 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -633,7 +756,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 5
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -674,7 +797,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR 1 // deltas always home to max
#define Y_HOME_DIR 1
#define Z_HOME_DIR 1
@@ -696,11 +819,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -725,75 +848,95 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
// Works best with 5 or more points in each dimension.
#define ABL_GRID_POINTS_X 7
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID // Deltas only support grid mode.
// Set the boundaries for probing (where the probe can reach).
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS-25)
#define LEFT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
#define FRONT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define BACK_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
// Set the rectangle in which to probe
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS-25)
#define LEFT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
#define FRONT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define BACK_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Non-linear bed leveling will be used.
// Compensate by interpolating between the nearest four Z probe values for each point.
// Useful for deltas where the print surface may appear like a bowl or dome shape.
// Works best with AUTO_BED_LEVELING_GRID_POINTS 5 or higher.
#define AUTO_BED_LEVELING_GRID_POINTS 7
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -822,37 +965,9 @@
#define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28).
#endif
// Delta only homes to Z
#define HOMING_FEEDRATE_Z (200*60)
//
// MOVEMENT SETTINGS
// @section motion
//
#define XYZ_FULL_STEPS_PER_ROTATION 200
#define XYZ_MICROSTEPS 32
#define XYZ_BELT_PITCH 2
#define XYZ_PULLEY_TEETH 20
#define XYZ_STEPS ((XYZ_FULL_STEPS_PER_ROTATION) * (XYZ_MICROSTEPS) / double(XYZ_BELT_PITCH) / double(XYZ_PULLEY_TEETH))
// default settings
// delta speeds must be the same on xyz
#define DEFAULT_AXIS_STEPS_PER_UNIT {XYZ_STEPS, XYZ_STEPS, XYZ_STEPS, 184.8}
#define DEFAULT_MAX_FEEDRATE {200, 200, 200, 200} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,9000,9000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 20.0 // (mm/sec)
#define DEFAULT_ZJERK 20.0 // (mm/sec) Must be same as XY for delta
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -880,8 +995,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -1022,9 +1137,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -1048,7 +1163,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1360,6 +1475,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -173,14 +173,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -208,18 +210,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -305,7 +322,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -367,6 +384,7 @@
#define DEFAULT_MINSEGMENTTIME 20000
// If defined the movements slow down when the look ahead buffer is only half full
// (don't use SLOWDOWN with DELTA because DELTA generates hundreds of segments per second)
//#define SLOWDOWN
// Frequency limit
@@ -411,6 +429,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -452,15 +473,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -489,6 +514,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -505,9 +560,20 @@
#define D_FILAMENT 2.85
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -536,7 +602,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -552,7 +629,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -569,7 +646,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -647,126 +724,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -779,27 +1066,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -81,8 +81,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(oxivanisher)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -98,14 +98,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -126,9 +135,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -162,69 +174,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 2
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 5
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -274,7 +303,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -326,8 +354,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 15.00
@@ -345,14 +371,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -380,9 +409,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
//===========================================================================
//============================== Delta Settings =============================
@@ -424,6 +457,11 @@
// in ultralcd.cpp@lcd_delta_calibrate_menu()
//#define DELTA_CALIBRATION_MENU
// After homing move down to a height where XY movement is unconstrained
#define DELTA_HOME_TO_SAFE_ZONE
//#define DELTA_ENDSTOP_ADJ { 0, 0, 0 }
#endif
// Enable this option for Toshiba steppers
@@ -468,16 +506,93 @@
#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
// variables to calculate steps
#define XYZ_FULL_STEPS_PER_ROTATION 200
#define XYZ_MICROSTEPS 16
#define XYZ_BELT_PITCH 2
#define XYZ_PULLEY_TEETH 16
// delta speeds must be the same on xyz
#define XYZ_STEPS (XYZ_FULL_STEPS_PER_ROTATION * XYZ_MICROSTEPS / double(XYZ_BELT_PITCH) / double(XYZ_PULLEY_TEETH))
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { XYZ_STEPS, XYZ_STEPS, XYZ_STEPS, 158 } // default steps per unit for PowerWasp
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 200, 200, 200, 25 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 9000, 9000, 9000, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 2000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 20.0
#define DEFAULT_YJERK 20.0
#define DEFAULT_ZJERK 20.0
#define DEFAULT_EJERK 20.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -489,6 +604,7 @@
#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -574,9 +690,6 @@
#endif // Z_PROBE_ALLEN_KEY
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -594,16 +707,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -612,20 +733,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 20 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 10 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 20 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 10 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -634,7 +760,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -675,7 +801,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR 1 // deltas always home to max
#define Y_HOME_DIR 1
#define Z_HOME_DIR 1
@@ -697,11 +823,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -726,75 +852,95 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
// Works best with 5 or more points in each dimension.
#define ABL_GRID_POINTS_X 5
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID // Deltas only support grid mode.
// Set the boundaries for probing (where the probe can reach).
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
#define LEFT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
#define FRONT_PROBE_BED_POSITION - (DELTA_PROBEABLE_RADIUS - 20)
#define BACK_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS - 40
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
// Set the rectangle in which to probe
#define DELTA_PROBEABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
#define LEFT_PROBE_BED_POSITION -(DELTA_PROBEABLE_RADIUS)
#define RIGHT_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS
#define FRONT_PROBE_BED_POSITION - (DELTA_PROBEABLE_RADIUS - 20)
#define BACK_PROBE_BED_POSITION DELTA_PROBEABLE_RADIUS - 40
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Non-linear bed leveling will be used.
// Compensate by interpolating between the nearest four Z probe values for each point.
// Useful for deltas where the print surface may appear like a bowl or dome shape.
// Works best with AUTO_BED_LEVELING_GRID_POINTS 5 or higher.
#define AUTO_BED_LEVELING_GRID_POINTS 5
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -826,36 +972,6 @@
// Delta only homes to Z
#define HOMING_FEEDRATE_Z (60*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// variables to calculate steps
#define XYZ_FULL_STEPS_PER_ROTATION 200
#define XYZ_MICROSTEPS 16
#define XYZ_BELT_PITCH 2
#define XYZ_PULLEY_TEETH 16
// delta speeds must be the same on xyz
#define XYZ_STEPS (XYZ_FULL_STEPS_PER_ROTATION * XYZ_MICROSTEPS / double(XYZ_BELT_PITCH) / double(XYZ_PULLEY_TEETH))
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {XYZ_STEPS, XYZ_STEPS, XYZ_STEPS, 158} // default steps per unit for PowerWasp
#define DEFAULT_MAX_FEEDRATE {200, 200, 200, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,9000,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 2000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 20.0 // (mm/sec)
#define DEFAULT_ZJERK 20.0 // (mm/sec)
#define DEFAULT_EJERK 20.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -883,8 +999,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -1025,9 +1141,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
#define LCD_LANGUAGE en
@@ -1051,7 +1167,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1363,6 +1479,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -407,6 +424,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -448,15 +468,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -485,6 +509,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -501,9 +555,20 @@
#define D_FILAMENT 2.85
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -532,7 +597,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -548,7 +624,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -565,7 +641,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -643,126 +719,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -775,27 +1061,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -133,9 +142,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -169,69 +181,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 12
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -281,7 +310,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -331,8 +359,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
@@ -350,14 +376,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -385,9 +414,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
//#define CONFIG_STEPPERS_TOSHIBA
@@ -431,16 +464,84 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 400, 400, 400, 163 } // default steps per unit for ***** MakiBox A6 *****
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 60, 60, 20, 45 }
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 2000, 2000, 30, 10000 }
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 20.0
#define DEFAULT_YJERK 20.0
#define DEFAULT_ZJERK 0.4
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -452,6 +553,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -496,9 +598,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -516,16 +615,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -534,20 +641,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -556,7 +668,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
@@ -597,7 +709,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -619,11 +731,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -648,71 +760,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -745,27 +879,6 @@
#define HOMING_FEEDRATE_XY 1500
#define HOMING_FEEDRATE_Z (2*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {400, 400, 400, 163} // default steps per unit for ***** MakiBox A6 *****
#define DEFAULT_MAX_FEEDRATE {60, 60, 20, 45} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {2000,2000,30,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 20.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -793,8 +906,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -935,9 +1048,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
//#define LCD_LANGUAGE en
@@ -961,7 +1074,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1273,6 +1386,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -387,7 +404,7 @@
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
#define DIGIPOT_I2C_NUM_CHANNELS 4
// actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
#define DIGIPOT_I2C_MOTOR_CURRENTS {1.7, 1.7, 1.7, 1.7}
#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.7, 1.7, 1.7, 1.7 }
//===========================================================================
//=============================Additional Features===========================
@@ -405,6 +422,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -446,15 +466,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -483,6 +507,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -499,9 +553,20 @@
#define D_FILAMENT 2.85
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -530,7 +595,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -546,7 +622,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -563,7 +639,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -641,126 +717,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -773,27 +1059,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

View File

@@ -88,8 +88,8 @@
// build by the user have been successfully uploaded into firmware.
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define SHOW_BOOTSCREEN
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during boot in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during boot in line 2
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
@@ -105,14 +105,23 @@
//#define SHOW_CUSTOM_BOOTSCREEN
// @section machine
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
// :[0,1,2,3,4,5,6,7]
/**
* Select which serial port on the board will be used for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
* :[0, 1, 2, 3, 4, 5, 6, 7]
*/
#define SERIAL_PORT 0
// This determines the communication speed of the printer
// :[2400,9600,19200,38400,57600,115200,250000]
/**
* This setting determines the communication speed of the printer.
*
* 250000 works in most cases, but you might try a lower speed if
* you commonly experience drop-outs during host printing.
*
* :[2400, 9600, 19200, 38400, 57600, 115200, 250000]
*/
#define BAUDRATE 250000
// Enable the Bluetooth serial interface on AT90USB devices
@@ -133,9 +142,12 @@
//#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
// This defines the number of extruders
// :[1,2,3,4]
// :[1, 2, 3, 4]
#define EXTRUDERS 1
// Enable if your E steppers or extruder gear ratios are not identical
//#define DISTINCT_E_FACTORS
// For Cyclops or any "multi-extruder" that shares a single nozzle.
//#define SINGLENOZZLE
@@ -169,69 +181,86 @@
//#define HOTEND_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
//#define HOTEND_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
// :{1:'ATX',2:'X-Box 360'}
/**
* Select your power supply here. Use 0 if you haven't connected the PS_ON_PIN
*
* 0 = No Power Switch
* 1 = ATX
* 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
*
* :{ 0:'No power switch', 1:'ATX', 2:'X-Box 360' }
*/
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
//#define PS_DEFAULT_OFF
#if POWER_SUPPLY > 0
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
#endif
// @section temperature
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -3 is thermocouple with MAX31855 (only for sensor 0)
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
// 66 is 4.7M High Temperature thermistor from Dyze Design
// 70 is the 100K thermistor found in the bq Hephestos 2
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
//#define DUMMY_THERMISTOR_998_VALUE 25
//#define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used",'1':"100k / 4.7k - EPCOS",'2':"200k / 4.7k - ATC Semitec 204GT-2",'3':"Mendel-parts / 4.7k",'4':"10k !! do not use for a hotend. Bad resolution at high temp. !!",'5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'6':"100k / 4.7k EPCOS - Not as accurate as Table 1",'7':"100k / 4.7k Honeywell 135-104LAG-J01",'8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT",'9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1",'10':"100k / 4.7k RS 198-961",'11':"100k / 4.7k beta 3950 1%",'12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)",'13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'",'20':"PT100 (Ultimainboard V2.x)",'51':"100k / 1k - EPCOS",'52':"200k / 1k - ATC Semitec 204GT-2",'55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)",'60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950",'66':"Dyze Design 4.7M High Temperature thermistor",'70':"the 100K thermistor found in the bq Hephestos 2",'71':"100k / 4.7k Honeywell 135-104LAF-J01",'147':"Pt100 / 4.7k",'1047':"Pt1000 / 4.7k",'110':"Pt100 / 1k (non-standard)",'1010':"Pt1000 / 1k (non standard)",'-3':"Thermocouple + MAX31855 (only for sensor 0)",'-2':"Thermocouple + MAX6675 (only for sensor 0)",'-1':"Thermocouple + AD595",'998':"Dummy 1",'999':"Dummy 2" }
/**
* --NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
*
* Temperature sensors available:
*
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
* 0 : not used
* 1 : 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
* 8 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
* 9 : 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
* 10 : 100k RS thermistor 198-961 (4.7k pullup)
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
* 70 : the 100K thermistor found in the bq Hephestos 2
*
* 1k ohm pullup tables - This is atypical, and requires changing out the 4.7k pullup for 1k.
* (but gives greater accuracy and more stable PID)
* 51 : 100k thermistor - EPCOS (1k pullup)
* 52 : 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
* 55 : 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
*
* 1047 : Pt1000 with 4k7 pullup
* 1010 : Pt1000 with 1k pullup (non standard)
* 147 : Pt100 with 4k7 pullup
* 110 : Pt100 with 1k pullup (non standard)
*
* Use these for Testing or Development purposes. NEVER for production machine.
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 5
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 100
// Use temp sensor 1 as a redundant sensor with sensor 0. If the readings
// from the two sensors differ too much the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
@@ -281,7 +310,6 @@
// 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
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define 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
@@ -318,8 +346,6 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER //limit for the integral term
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
@@ -337,14 +363,17 @@
// @section extruder
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
//===========================================================================
//======================== Thermal Runaway Protection =======================
@@ -372,9 +401,13 @@
// @section machine
// Uncomment one of these options to enable CoreXY, CoreXZ, or CoreYZ kinematics
// either in the usual order or reversed
//#define COREXY
//#define COREXZ
//#define COREYZ
//#define COREYX
//#define COREZX
//#define COREZY
// Enable this option for Toshiba steppers
#define CONFIG_STEPPERS_TOSHIBA
@@ -418,16 +451,90 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
// @section motion
/**
* Default Settings
*
* These settings can be reset by M502
*
* You can set distinct factors for each E stepper, if needed.
* If fewer factors are given, the last will apply to the rest.
*
* Note that if EEPROM is enabled, saved values will override these.
*/
/**
* Default Axis Steps Per Unit (steps/mm)
* Override with M92
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_AXIS_STEPS_PER_UNIT { 71.1, 71.1, 2560, 600 } // David TVRR
//#define DEFAULT_AXIS_STEPS_PER_UNIT { 79.87, 79.87, 2566, 563.78 } // Al's TVRR
//#define DEFAULT_AXIS_STEPS_PER_UNIT { 81.26, 80.01, 2561, 599.14 } // Michel TVRR old
//#define DEFAULT_AXIS_STEPS_PER_UNIT { 71.1, 71.1, 2560, 739.65 } // Michel TVRR
/**
* Default Max Feed Rate (mm/s)
* Override with M203
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_FEEDRATE { 500, 500, 5, 45 } // David TVRR
/**
* Default Max Acceleration (change/s) change = mm/s
* (Maximum start speed for accelerated moves)
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3]]]
*/
#define DEFAULT_MAX_ACCELERATION { 9000, 9000, 100, 10000 }
/* MICHEL: This has an impact on the "ripples" in print walls */
/**
* Default Acceleration (change/s) change = mm/s
* Override with M204
*
* M204 P Acceleration
* M204 R Retract Acceleration
* M204 T Travel Acceleration
*/
#define DEFAULT_ACCELERATION 500 // X, Y, Z and E acceleration for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration for retracts
#define DEFAULT_TRAVEL_ACCELERATION 500 // X, Y, Z acceleration for travel (non printing) moves
/**
* Default Jerk (mm/s)
*
* "Jerk" specifies the minimum speed change that requires acceleration.
* When changing speed and direction, if the difference is less than the
* value set here, it may happen instantaneously.
*/
#define DEFAULT_XJERK 20.0
#define DEFAULT_YJERK 20.0
#define DEFAULT_ZJERK 0.4
#define DEFAULT_EJERK 5.0
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
// @section probes
//
// Probe Type
// Probes are sensors/switches that are activated / deactivated before/after use.
//
// Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc.
// You must activate one of these to use AUTO_BED_LEVELING_FEATURE below.
// You must activate one of these to use Auto Bed Leveling below.
//
// Use M851 to set the Z probe vertical offset from the nozzle. Store with M500.
//
@@ -439,6 +546,7 @@
//#define FIX_MOUNTED_PROBE
// The BLTouch probe emulates a servo probe.
// The default connector is SERVO 0. Set Z_ENDSTOP_SERVO_NR below to override.
//#define BLTOUCH
// Z Servo Probe, such as an endstop switch on a rotating arm.
@@ -483,9 +591,6 @@
// Allen Key Probe is defined in the Delta example configurations.
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
// *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! ***
//
// To continue using the Z-min-endstop for homing, be sure to disable Z_SAFE_HOMING.
@@ -503,16 +608,24 @@
// - normally-open switches to 5V and D32.
//
// Normally-closed switches are advised and are the default.
//
//
// The Z_MIN_PROBE_PIN sets the Arduino pin to use. (See your board's pins file.)
// Since the RAMPS Aux4->D32 pin maps directly to the Arduino D32 pin, D32 is the
// default pin for all RAMPS-based boards. Some other boards map differently.
// To set or change the pin for your board, edit the appropriate pins_XXXXX.h file.
// default pin for all RAMPS-based boards. Most boards use the X_MAX_PIN by default.
// To use a different pin you can override it here.
//
// WARNING:
// Setting the wrong pin may have unexpected and potentially disastrous consequences.
// Use with caution and do your homework.
//
//#define Z_MIN_PROBE_PIN X_MAX_PIN
//
// Enable Z_MIN_PROBE_ENDSTOP to use _both_ a Z Probe and a Z-min-endstop on the same machine.
// With this option the Z_MIN_PROBE_PIN will only be used for probing, never for homing.
//
//#define Z_MIN_PROBE_ENDSTOP
// Enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN to use the Z_MIN_PIN for your Z_MIN_PROBE.
@@ -521,20 +634,25 @@
// To use a probe you must enable one of the two options above!
// This option disables the use of the Z_MIN_PROBE_PIN
// To enable the Z probe pin but disable its use, uncomment the line below. This only affects a
// Z probe switch if you have a separate Z min endstop also and have activated Z_MIN_PROBE_ENDSTOP above.
// If you're using the Z MIN endstop connector for your Z probe, this has no effect.
//#define DISABLE_Z_MIN_PROBE_ENDSTOP
// Enable Z Probe Repeatability test to see how accurate your probe is
//#define Z_MIN_PROBE_REPEATABILITY_TEST
//
// Probe Raise options provide clearance for the probe to deploy, stow, and travel.
//
#define Z_PROBE_DEPLOY_HEIGHT 15 // Raise to make room for the probe to deploy / stow
#define Z_PROBE_TRAVEL_HEIGHT 5 // Raise between probing points.
/**
* Z probes require clearance when deploying, stowing, and moving between
* probe points to avoid hitting the bed and other hardware.
* Servo-mounted probes require extra space for the arm to rotate.
* Inductive probes need space to keep from triggering early.
*
* Use these settings to specify the distance (mm) to raise the probe (or
* lower the bed). The values set here apply over and above any (negative)
* probe Z Offset set with Z_PROBE_OFFSET_FROM_EXTRUDER, M851, or the LCD.
* Only integer values >= 1 are valid here.
*
* Example: `M851 Z-5` with a CLEARANCE of 4 => 9mm from bed to nozzle.
* But: `M851 Z+1` with a CLEARANCE of 2 => 2mm from bed to nozzle.
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
//
// For M851 give a range for adjusting the Z probe offset
@@ -543,7 +661,7 @@
#define Z_PROBE_OFFSET_RANGE_MAX 20
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
// :{0:'Low',1:'High'}
// :{ 0:'Low', 1:'High' }
#define X_ENABLE_ON 1
#define Y_ENABLE_ON 1
#define Z_ENABLE_ON 1
@@ -584,7 +702,7 @@
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
// :[-1,1]
// :[-1, 1]
#define X_HOME_DIR -1
#define Y_HOME_DIR -1
#define Z_HOME_DIR -1
@@ -606,11 +724,11 @@
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// RAMPS-based boards use SERVO3_PIN. For other boards you may need to define FIL_RUNOUT_PIN.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
const bool FIL_RUNOUT_INVERTING = false; // set to true to invert the logic of the sensor.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -635,71 +753,93 @@
#define MBL_Z_STEP 0.025 // Step size while manually probing Z axis.
#endif // MANUAL_BED_LEVELING
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//============================ Auto Bed Leveling ============================
//===========================================================================
// @section bedlevel
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
/**
* Select one form of Auto Bed Leveling below.
*
* If you're also using the Probe for Z Homing, it's
* highly recommended to enable Z_SAFE_HOMING also!
*
* - 3POINT
* Probe 3 arbitrary points on the bed (that aren't collinear)
* You specify the XY coordinates of all 3 points.
* The result is a single tilted plane. Best for a flat bed.
*
* - LINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a single tilted plane. Best for a flat bed.
*
* - BILINEAR
* Probe several points in a grid.
* You specify the rectangle and the density of sample points.
* The result is a mesh, best for large or uneven beds.
*/
//#define AUTO_BED_LEVELING_3POINT
//#define AUTO_BED_LEVELING_LINEAR
//#define AUTO_BED_LEVELING_BILINEAR
// Enable this feature to get detailed logging of G28, G29, M48, etc.
// Logging is off by default. Enable this logging feature with 'M111 S32'.
// NOTE: Requires a huge amount of PROGMEM.
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
* NOTE: Requires a lot of PROGMEM!
*/
//#define DEBUG_LEVELING_FEATURE
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
// There are 2 different ways to specify probing locations:
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't collinear)
// You specify the XY coordinates of all 3 points.
// Set the number of grid points per dimension.
#define ABL_GRID_POINTS_X 3
#define ABL_GRID_POINTS_Y ABL_GRID_POINTS_X
// Enable this to sample the bed in a grid (least squares solution).
// Note: this feature generates 10KB extra code size.
#define AUTO_BED_LEVELING_GRID
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
#if ENABLED(AUTO_BED_LEVELING_GRID)
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
#define MIN_PROBE_EDGE 10 // The Z probe minimum square sides can be no smaller than this.
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
// Gradually reduce leveling correction until a set height is reached,
// at which point movement will be level to the machine's XY plane.
// The height can be set with M420 Z<height>
#define ENABLE_LEVELING_FADE_HEIGHT
#endif
// Set the number of grid points per dimension.
// You probably don't need more than 3 (squared=9).
#define AUTO_BED_LEVELING_GRID_POINTS 2
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
#else // !AUTO_BED_LEVELING_GRID
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
// Arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif
#endif // !AUTO_BED_LEVELING_GRID
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" // These commands will be executed in the end of G29 routine.
// Useful to retract a deployable Z probe.
// If you've enabled AUTO_BED_LEVELING_FEATURE and are using the Z Probe for Z Homing,
// it is highly recommended you also enable Z_SAFE_HOMING below!
#endif // AUTO_BED_LEVELING_FEATURE
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
*/
//#define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10"
// @section homing
@@ -732,31 +872,6 @@
#define HOMING_FEEDRATE_XY (50*60)
#define HOMING_FEEDRATE_Z (4*60)
//
// MOVEMENT SETTINGS
// @section motion
//
// default settings
//#define DEFAULT_AXIS_STEPS_PER_UNIT {79.87, 79.87, 2566, 563,78} // Al's TVRR
//#define DEFAULT_AXIS_STEPS_PER_UNIT {81.26, 80.01, 2561, 599.14} // Michel TVRR old
//#define DEFAULT_AXIS_STEPS_PER_UNIT {71.1, 71.1, 2560, 739.65} // Michel TVRR
#define DEFAULT_AXIS_STEPS_PER_UNIT {71.1, 71.1, 2560, 600} // David TVRR
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 45} // (mm/sec) David TVRR
#define DEFAULT_MAX_ACCELERATION {9000,9000,100,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
/* MICHEL: This has an impact on the "ripples" in print walls */
#define DEFAULT_ACCELERATION 500 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 500 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 20.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
@@ -784,8 +899,8 @@
// When enabled Marlin will send a busy status message to the host
// every couple of seconds when it can't accept commands.
//
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
#define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages
#define DEFAULT_KEEPALIVE_INTERVAL 2 // Number of seconds between "busy" messages. Set with M113.
//
// M100 Free Memory Watcher
@@ -926,9 +1041,9 @@
// Here you may choose the language used by Marlin on the LCD menus, the following
// list of languages are available:
// en, an, bg, ca, cn, cz, de, el, el-gr, es, eu, fi, fr, gl, hr, it,
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, test
// kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, test
//
// :{'en':'English','an':'Aragonese','bg':'Bulgarian','ca':'Catalan','cn':'Chinese','cz':'Czech','de':'German','el':'Greek','el-gr':'Greek (Greece)','es':'Spanish','eu':'Basque-Euskera','fi':'Finnish','fr':'French','gl':'Galician','hr':'Croatian','it':'Italian','kana':'Japanese','kana_utf8':'Japanese (UTF8)','nl':'Dutch','pl':'Polish','pt':'Portuguese','pt-br':'Portuguese (Brazilian)','pt-br_utf8':'Portuguese (Brazilian UTF8)','pt_utf8':'Portuguese (UTF8)','ru':'Russian','test':'TEST'}
// :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' }
//
//#define LCD_LANGUAGE en
@@ -952,7 +1067,7 @@
//
// See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
//
// :['JAPANESE','WESTERN','CYRILLIC']
// :['JAPANESE', 'WESTERN', 'CYRILLIC']
//
#define DISPLAY_CHARSET_HD44780 JAPANESE
@@ -1264,6 +1379,14 @@
//define BlinkM/CyzRgb Support
//#define BLINKM
// Support for an RGB LED using 3 separate pins with optional PWM
//#define RGB_LED
#if ENABLED(RGB_LED)
#define RGB_LED_R_PIN 34
#define RGB_LED_G_PIN 43
#define RGB_LED_B_PIN 35
#endif
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas

View File

@@ -168,14 +168,16 @@
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_ESTEPS 14 // mm filament
#define EXTRUDER_RUNOUT_SPEED 1500 // extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
@@ -203,18 +205,33 @@
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
/**
* Extruder cooling fans
*
* Extruder auto fans automatically turn on when their extruders'
* temperatures go above EXTRUDER_AUTO_FAN_TEMPERATURE.
*
* Your board's pins file specifies the recommended pins. Override those here
* or set to -1 to disable completely.
*
* Multiple extruders can be assigned to the same pin in which case
* the fan will turn on when any selected extruder is above the threshold.
*/
#define E0_AUTO_FAN_PIN -1
#define E1_AUTO_FAN_PIN -1
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Define a pin to turn case light on/off
//#define CASE_LIGHT_PIN 4
#if PIN_EXISTS(CASE_LIGHT)
#define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low)
//#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on
//#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu
#endif
//===========================================================================
//============================ Mechanical Settings ==========================
//===========================================================================
@@ -300,7 +317,7 @@
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
#define DEFAULT_DUAL_X_CARRIAGE_MODE DXC_FULL_CONTROL_MODE
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
@@ -405,6 +422,9 @@
// Include a page of printer information in the LCD Main Menu
//#define LCD_INFO_MENU
// On the Info Screen, display XY with one decimal place when possible
//#define LCD_DECIMAL_SMALL_XY
#if ENABLED(SDSUPPORT)
// Some RAMPS and other boards don't detect when an SD card is inserted. You can work
@@ -446,15 +466,19 @@
#endif // SDSUPPORT
// for dogm lcd displays you can choose some additional fonts:
// Some additional options are available for graphical displays:
#if ENABLED(DOGLCD)
// save 3120 bytes of PROGMEM by commenting out #define USE_BIG_EDIT_FONT
// we don't have a big font for Cyrillic, Kana
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
// If you have spare 2300Byte of progmem and want to use a
// smaller font on the Info-screen uncomment the next line.
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// 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.
//#define DOGM_SPI_DELAY_US 5
#endif // DOGLCD
// @section safety
@@ -483,6 +507,36 @@
#define BABYSTEP_MULTIPLICATOR 1 //faster movements
#endif
//
// Ensure Smooth Moves
//
// Enable this option to prevent the machine from stuttering when printing multiple short segments.
// This feature uses two strategies to eliminate stuttering:
//
// 1. During short segments a Graphical LCD update may take so much time that the planner buffer gets
// completely drained. When this happens pauses are introduced between short segments, and print moves
// will become jerky until a longer segment provides enough time for the buffer to be filled again.
// This jerkiness negatively affects print quality. The ENSURE_SMOOTH_MOVES option addresses the issue
// by pausing the LCD until there's enough time to safely update.
//
// NOTE: This will cause the Info Screen to lag and controller buttons may become unresponsive.
// Enable ALWAYS_ALLOW_MENU to keep the controller responsive.
//
// 2. No block is allowed to take less time than MIN_BLOCK_TIME. That's the time it takes in the main
// loop to add a new block to the buffer, check temperatures, etc., including all blocked time due to
// interrupts (without LCD update). By enforcing a minimum time-per-move, the buffer is prevented from
// draining.
//
//#define ENSURE_SMOOTH_MOVES
#if ENABLED(ENSURE_SMOOTH_MOVES)
//#define ALWAYS_ALLOW_MENU // If enabled, the menu will always be responsive.
// WARNING: Menu navigation during short moves may cause stuttering!
#define LCD_UPDATE_THRESHOLD 135 // (ms) Minimum duration for the current segment to allow an LCD update.
// Default value is good for graphical LCDs (e.g., REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER).
// You may try to lower this value until you printer starts stuttering again as if ENSURE_SMOOTH_MOVES is disabled.
#define MIN_BLOCK_TIME 6 // (ms) Minimum duration of a single block. You shouldn't need to modify this.
#endif
// @section extruder
// extruder advance constant (s2/mm3)
@@ -499,9 +553,20 @@
#define D_FILAMENT 2.85
#endif
// Implementation of a linear pressure control
// Assumption: advance = k * (delta velocity)
// K=0 means advance disabled. A good value for a gregs wade extruder will be around K=75
/**
* Implementation of linear pressure control
*
* Assumption: advance = k * (delta velocity)
* K=0 means advance disabled.
* To get a rough start value for calibration, measure your "free filament length"
* between the hobbed bolt and the nozzle (in cm). Use the formula below that fits
* your setup, where L is the "free filament length":
*
* Filament diameter | 1.75mm | 3.0mm |
* ----------------------------|-----------|------------|
* Stiff filament (PLA) | K=47*L/10 | K=139*L/10 |
* Softer filament (ABS, nGen) | K=88*L/10 | K=260*L/10 |
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
@@ -530,7 +595,18 @@
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
//#define BEZIER_CURVE_SUPPORT
const unsigned int dropsegments = 5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// G38.2 and G38.3 Probe Target
//#define 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)
#endif
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
// @section temperature
@@ -546,7 +622,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
@@ -563,7 +639,7 @@ const unsigned int dropsegments = 5; //everything with less than this number of
// For ADVANCED_OK (M105) you need 32 bytes.
// For debug-echo: 128 bytes for the optimal speed.
// Other output doesn't need to be that speedy.
// :[0,2,4,8,16,32,64,128,256]
// :[0, 2, 4, 8, 16, 32, 64, 128, 256]
#define TX_BUFFER_SIZE 0
// Enable an emergency-command parser to intercept certain commands as they
@@ -641,126 +717,336 @@ const unsigned int dropsegments = 5; //everything with less than this number of
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
//#define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
//#define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
//#define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
//#define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
//#define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
//#define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
//#define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
//#define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
//#define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
#define X_MICROSTEPS 16 // number of microsteps
#define X2_MAX_CURRENT 1000
#define X2_SENSE_RESISTOR 91
#define X2_MICROSTEPS 16
#define Y_MAX_CURRENT 1000
#define Y_SENSE_RESISTOR 91
#define Y_MICROSTEPS 16
#define Y2_MAX_CURRENT 1000
#define Y2_SENSE_RESISTOR 91
#define Y2_MICROSTEPS 16
#define Z_MAX_CURRENT 1000
#define Z_SENSE_RESISTOR 91
#define Z_MICROSTEPS 16
#define Z2_MAX_CURRENT 1000
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
#define E1_MAX_CURRENT 1000
#define E1_SENSE_RESISTOR 91
#define E1_MICROSTEPS 16
#define E2_MAX_CURRENT 1000
#define E2_SENSE_RESISTOR 91
#define E2_MICROSTEPS 16
#define E3_MAX_CURRENT 1000
#define E3_SENSE_RESISTOR 91
#define E3_MICROSTEPS 16
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the Arduino IDE for this
******************************************************************************/
// @section TMC2130
// @section l6470
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
*
* To use TMC2130 drivers in SPI mode, you'll also need the TMC2130 Arduino library
* (https://github.com/makertum/Trinamic_TMC2130).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130DRIVER
#if ENABLED(HAVE_TMC2130DRIVER)
//#define TMC2130_ADVANCED_CONFIGURATION
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
#if ENABLED(TMC2130_ADVANCED_CONFIGURATION)
// If you've enabled TMC2130_ADVANCED_CONFIGURATION, define global settings below.
// Enabled settings will be automatically applied to all axes specified above.
//
// Please read the TMC2130 datasheet:
// http://www.trinamic.com/_articles/products/integrated-circuits/tmc2130/_datasheet/TMC2130_datasheet.pdf
// All settings here have the same (sometimes cryptic) names as in the datasheet.
//
// The following, uncommented settings are only suggestion.
/* GENERAL CONFIGURATION */
//#define GLOBAL_EN_PWM_MODE 0
#define GLOBAL_I_SCALE_ANALOG 1 // [0,1] 0: Normal, 1: AIN
//#define GLOBAL_INTERNAL_RSENSE 0 // [0,1] 0: Normal, 1: Internal
#define GLOBAL_EN_PWM_MODE 0 // [0,1] 0: Normal, 1: stealthChop with velocity threshold
//#define GLOBAL_ENC_COMMUTATION 0 // [0,1]
#define GLOBAL_SHAFT 0 // [0,1] 0: normal, 1: invert
//#define GLOBAL_DIAG0_ERROR 0 // [0,1]
//#define GLOBAL_DIAG0_OTPW 0 // [0,1]
//#define GLOBAL_DIAG0_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_STALL 0 // [0,1]
//#define GLOBAL_DIAG1_INDEX 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG1_ONSTATE 0 // [0,1]
//#define GLOBAL_DIAG0_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_DIAG1_INT_PUSHPULL 0 // [0,1]
//#define GLOBAL_SMALL_HYSTERESIS 0 // [0,1]
//#define GLOBAL_STOP_ENABLE 0 // [0,1]
//#define GLOBAL_DIRECT_MODE 0 // [0,1]
/* VELOCITY-DEPENDENT DRIVE FEATURES */
#define GLOBAL_IHOLD 22 // [0-31] 0: min, 31: max
#define GLOBAL_IRUN 31 // [0-31] 0: min, 31: max
#define GLOBAL_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
//#define GLOBAL_TPOWERDOWN 0 // [0-255] 0: min, 255: about 4 seconds
//#define GLOBAL_TPWMTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
//#define GLOBAL_TCOOLTHRS 0 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
#define GLOBAL_THIGH 10 // [0-1048576] e.g. 20 corresponds with 2000 steps/s
/* SPI MODE CONFIGURATION */
//#define GLOBAL_XDIRECT 0
/* DCSTEP MINIMUM VELOCITY */
//#define GLOBAL_VDCMIN 0
/* MOTOR DRIVER CONFIGURATION*/
//#define GLOBAL_DEDGE 0
//#define GLOBAL_DISS2G 0
#define GLOBAL_INTPOL 1 // 0: off 1: 256 microstep interpolation
#define GLOBAL_MRES 16 // number of microsteps
#define GLOBAL_SYNC 1 // [0-15]
#define GLOBAL_VHIGHCHM 1 // [0,1] 0: normal, 1: high velocity stepper mode
#define GLOBAL_VHIGHFS 0 // [0,1] 0: normal, 1: switch to full steps for high velocities
// #define GLOBAL_VSENSE 0 // [0,1] 0: normal, 1: high sensitivity (not recommended)
#define GLOBAL_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define GLOBAL_CHM 0 // [0,1] 0: spreadCycle, 1: Constant off time with fast decay time.
//#define GLOBAL_RNDTF 0
//#define GLOBAL_DISFDCC 0
//#define GLOBAL_FD 0
//#define GLOBAL_HEND 0
//#define GLOBAL_HSTRT 0
#define GLOBAL_TOFF 10 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
//#define GLOBAL_SFILT 0
//#define GLOBAL_SGT 0
//#define GLOBAL_SEIMIN 0
//#define GLOBAL_SEDN 0
//#define GLOBAL_SEMAX 0
//#define GLOBAL_SEUP 0
//#define GLOBAL_SEMIN 0
//#define GLOBAL_DC_TIME 0
//#define GLOBAL_DC_SG 0
//#define GLOBAL_FREEWHEEL 0
//#define GLOBAL_PWM_SYMMETRIC 0
//#define GLOBAL_PWM_AUTOSCALE 0
//#define GLOBAL_PWM_FREQ 0
//#define GLOBAL_PWM_GRAD 0
//#define GLOBAL_PWM_AMPL 0
//#define GLOBAL_ENCM_CTRL 0
#else
#define X_IHOLD 31 // [0-31] 0: min, 31: max
#define X_IRUN 31 // [0-31] 0: min, 31: max
#define X_IHOLDDELAY 15 // [0-15] 0: min, 15: about 4 seconds
#define X_I_SCALE_ANALOG 1 // 0: Normal, 1: AIN
#define X_MRES 16 // number of microsteps
#define X_TBL 1 // 0-3: set comparator blank time to 16, 24, 36 or 54 clocks, 1 or 2 is recommended
#define X_TOFF 8 // 0: driver disable, 1: use only with TBL>2, 2-15: off time setting during slow decay phase
#define X2_IHOLD 31
#define X2_IRUN 31
#define X2_IHOLDDELAY 15
#define X2_I_SCALE_ANALOG 1
#define X2_MRES 16
#define X2_TBL 1
#define X2_TOFF 8
#define Y_IHOLD 31
#define Y_IRUN 31
#define Y_IHOLDDELAY 15
#define Y_I_SCALE_ANALOG 1
#define Y_MRES 16
#define Y_TBL 1
#define Y_TOFF 8
#define Y2_IHOLD 31
#define Y2_IRUN 31
#define Y2_IHOLDDELAY 15
#define Y2_I_SCALE_ANALOG 1
#define Y2_MRES 16
#define Y2_TBL 1
#define Y2_TOFF 8
#define Z_IHOLD 31
#define Z_IRUN 31
#define Z_IHOLDDELAY 15
#define Z_I_SCALE_ANALOG 1
#define Z_MRES 16
#define Z_TBL 1
#define Z_TOFF 8
#define Z2_IHOLD 31
#define Z2_IRUN 31
#define Z2_IHOLDDELAY 15
#define Z2_I_SCALE_ANALOG 1
#define Z2_MRES 16
#define Z2_TBL 1
#define Z2_TOFF 8
#define E0_IHOLD 31
#define E0_IRUN 31
#define E0_IHOLDDELAY 15
#define E0_I_SCALE_ANALOG 1
#define E0_MRES 16
#define E0_TBL 1
#define E0_TOFF 8
#define E1_IHOLD 31
#define E1_IRUN 31
#define E1_IHOLDDELAY 15
#define E1_I_SCALE_ANALOG 1
#define E1_MRES 16
#define E1_TBL 1
#define E1_TOFF 8
#define E2_IHOLD 31
#define E2_IRUN 31
#define E2_IHOLDDELAY 15
#define E2_I_SCALE_ANALOG 1
#define E2_MRES 16
#define E2_TBL 1
#define E2_TOFF 8
#define E3_IHOLD 31
#define E3_IRUN 31
#define E3_IHOLDDELAY 15
#define E3_I_SCALE_ANALOG 1
#define E3_MRES 16
#define E3_TBL 1
#define E3_TOFF 8
#endif // TMC2130_ADVANCED_CONFIGURATION
#endif // HAVE_TMC2130DRIVER
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define X2_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
//#define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#endif
@@ -773,27 +1059,43 @@ const unsigned int dropsegments = 5; //everything with less than this number of
*
* ; Example #1
* ; This macro send the string "Marlin" to the slave device with address 0x63 (99)
* ; It uses multiple M155 commands with one B<base 10> arg
* M155 A99 ; Target slave address
* M155 B77 ; M
* M155 B97 ; a
* M155 B114 ; r
* M155 B108 ; l
* M155 B105 ; i
* M155 B110 ; n
* M155 S1 ; Send the current buffer
* ; It uses multiple M260 commands with one B<base 10> arg
* M260 A99 ; Target slave address
* M260 B77 ; M
* M260 B97 ; a
* M260 B114 ; r
* M260 B108 ; l
* M260 B105 ; i
* M260 B110 ; n
* M260 S1 ; Send the current buffer
*
* ; Example #2
* ; Request 6 bytes from slave device with address 0x63 (99)
* M156 A99 B5
* M261 A99 B5
*
* ; Example #3
* ; Example serial output of a M156 request
* ; Example serial output of a M261 request
* echo:i2c-reply: from:99 bytes:5 data:hello
*/
// @section i2cbus
//#define EXPERIMENTAL_I2CBUS
#define I2C_SLAVE_ADDRESS 0 // Set a value from 8 to 127 to act as a slave
/**
* Add M43 command for pins info and testing
*/
//#define PINS_DEBUGGING
/**
* Auto-report temperatures with M155 S<seconds>
*/
//#define AUTO_REPORT_TEMPERATURES
/**
* Include capabilities in M115 output
*/
//#define EXTENDED_CAPABILITIES_REPORT
#endif // CONFIGURATION_ADV_H

File diff suppressed because it is too large Load Diff

View File

@@ -25,6 +25,9 @@
#include "MarlinConfig.h"
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
// Fallback if no language is set. DON'T CHANGE
#ifndef LCD_LANGUAGE
#define LCD_LANGUAGE en
@@ -67,6 +70,8 @@
// pt-br_utf8 Portuguese (Brazilian UTF8)
// pt_utf8 Portuguese (UTF8)
// ru Russian
// tr Turkish
// uk Ukrainian
#ifdef DEFAULT_SOURCE_CODE_URL
#undef SOURCE_CODE_URL
@@ -125,7 +130,7 @@
#define MSG_INVALID_EXTRUDER "Invalid extruder"
#define MSG_INVALID_SOLENOID "Invalid solenoid"
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID EMERGENCY_PARSER_CAPABILITIES "\n"
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin " DETAILED_BUILD_VERSION " SOURCE_CODE_URL:" SOURCE_CODE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID
#define MSG_COUNT_X " Count X: "
#define MSG_COUNT_A " Count A: "
#define MSG_ERR_KILLED "Printer halted. kill() called!"
@@ -142,11 +147,14 @@
#define MSG_Y_MAX "y_max: "
#define MSG_Z_MIN "z_min: "
#define MSG_Z_MAX "z_max: "
#define MSG_Z2_MIN "z2_min: "
#define MSG_Z2_MAX "z2_max: "
#define MSG_Z_PROBE "z_probe: "
#define MSG_ERR_MATERIAL_INDEX "M145 S<index> out of range (0-1)"
#define MSG_ERR_M421_PARAMETERS "M421 requires XYZ or IJZ parameters"
#define MSG_ERR_MESH_XY "Mesh XY or IJ cannot be resolved"
#define MSG_ERR_ARC_ARGS "G2/G3 bad parameters"
#define MSG_ERR_PROTECTED_PIN "Protected Pin"
#define MSG_ERR_M428_TOO_FAR "Too far from reference point"
#define MSG_ERR_M303_DISABLED "PIDTEMP disabled"
#define MSG_M119_REPORT "Reporting endstop status"
@@ -154,6 +162,9 @@
#define MSG_ENDSTOP_OPEN "open"
#define MSG_HOTEND_OFFSET "Hotend offsets:"
#define MSG_DUPLICATION_MODE "Duplication mode: "
#define MSG_SOFT_ENDSTOPS "Soft endstops: "
#define MSG_SOFT_MIN " Min: "
#define MSG_SOFT_MAX " Max: "
#define MSG_SD_CANT_OPEN_SUBDIR "Cannot open subdir "
#define MSG_SD_INIT_FAIL "SD init fail"
@@ -238,7 +249,44 @@
#define LANGUAGE_INCL(M) LANGUAGE_INCL_(M)
#define INCLUDE_LANGUAGE LANGUAGE_INCL(LCD_LANGUAGE)
// Never translate these strings
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_H1 "1"
#define MSG_H2 "2"
#define MSG_H3 "3"
#define MSG_H4 "4"
#define MSG_N1 " 1"
#define MSG_N2 " 2"
#define MSG_N3 " 3"
#define MSG_N4 " 4"
#define MSG_E1 " E1"
#define MSG_E2 " E2"
#define MSG_E3 " E3"
#define MSG_E4 " E4"
#define MSG_MOVE_E1 "1"
#define MSG_MOVE_E2 "2"
#define MSG_MOVE_E3 "3"
#define MSG_MOVE_E4 "4"
#define MSG_DIAM_E1 " 1"
#define MSG_DIAM_E2 " 2"
#define MSG_DIAM_E3 " 3"
#define MSG_DIAM_E4 " 4"
#include INCLUDE_LANGUAGE
#if DISABLED(SIMULATE_ROMFONT) \
&& DISABLED(DISPLAY_CHARSET_ISO10646_1) \
&& DISABLED(DISPLAY_CHARSET_ISO10646_5) \
&& DISABLED(DISPLAY_CHARSET_ISO10646_KANA) \
&& DISABLED(DISPLAY_CHARSET_ISO10646_GREEK) \
&& DISABLED(DISPLAY_CHARSET_ISO10646_CN) \
&& DISABLED(DISPLAY_CHARSET_ISO10646_TR)
#define DISPLAY_CHARSET_ISO10646_1 // use the better font on full graphic displays.
#endif
#include "language_en.h"
#endif //__LANGUAGE_H

View File

@@ -30,8 +30,6 @@
#ifndef LANGUAGE_AN_H
#define LANGUAGE_AN_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " parada."
@@ -88,14 +86,11 @@
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_ACC "Acel"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ves-jerk"
#define MSG_VMAX "Vmax"
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax"

View File

@@ -31,19 +31,22 @@
#define LANGUAGE_BG_H
#define MAPPER_D0D1 // For Cyrillic
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_5
#define WELCOME_MSG MACHINE_NAME " Готов."
#define MSG_SD_INSERTED "Картата е поставена"
#define MSG_SD_REMOVED "Картата е извадена"
#define MSG_LCD_ENDSTOPS "Endstops" // Max length 8 characters
#define MSG_MAIN "Меню"
#define MSG_AUTOSTART "Автостарт"
#define MSG_DISABLE_STEPPERS "Изкл. двигатели"
#define MSG_AUTO_HOME "Паркиране"
#define MSG_AUTO_HOME_X "Home X"
#define MSG_AUTO_HOME_Y "Home Y"
#define MSG_AUTO_HOME_Z "Home Z"
#define MSG_LEVEL_BED_HOMING "Homing XYZ"
#define MSG_LEVEL_BED_WAITING "Click to Begin"
#define MSG_LEVEL_BED_NEXT_POINT "Next Point"
#define MSG_LEVEL_BED_DONE "Leveling Done!"
#define MSG_LEVEL_BED_CANCEL "Cancel"
#define MSG_SET_HOME_OFFSETS "Задай Начало"
@@ -74,6 +77,7 @@
#define MSG_MOVE_1MM "Премести с 1mm"
#define MSG_MOVE_10MM "Премести с 10mm"
#define MSG_SPEED "Скорост"
#define MSG_BED_Z "Bed Z"
#define MSG_NOZZLE LCD_STR_THERMOMETER " Дюза"
#define MSG_BED LCD_STR_THERMOMETER " Легло"
#define MSG_FAN_SPEED "Вентилатор"
@@ -89,19 +93,18 @@
#define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_SELECT "Select"
#define MSG_ACC "Acc"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "
#define MSG_A_RETRACT "A-откат"
#define MSG_A_TRAVEL "A-travel"
#define MSG_XSTEPS "X стъпки/mm"
#define MSG_YSTEPS "Y стъпки/mm"
#define MSG_ZSTEPS "Z стъпки/mm"
@@ -143,6 +146,8 @@
#define MSG_INIT_SDCARD "Иниц. SD-Карта"
#define MSG_CNG_SDCARD "Смяна SD-Карта"
#define MSG_ZPROBE_OUT "Z-сондата е извадена"
#define MSG_BLTOUCH_SELFTEST "BLTouch Self-Test"
#define MSG_BLTOUCH_RESET "Reset BLTouch"
#define MSG_HOME "Home" // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST
#define MSG_FIRST "first"
#define MSG_ZPROBE_ZOFFSET "Z Отстояние"
@@ -150,10 +155,91 @@
#define MSG_BABYSTEP_Y "Министъпка Y"
#define MSG_BABYSTEP_Z "Министъпка Z"
#define MSG_ENDSTOP_ABORT "Стоп Кр.Изключватели"
#define MSG_HEATING_FAILED_LCD "Heating failed"
#define MSG_ERR_REDUNDANT_TEMP "Err: REDUNDANT TEMP"
#define MSG_THERMAL_RUNAWAY "THERMAL RUNAWAY"
#define MSG_ERR_MAXTEMP "Err: MAXTEMP"
#define MSG_ERR_MINTEMP "Err: MINTEMP"
#define MSG_ERR_MAXTEMP_BED "Err: MAXTEMP BED"
#define MSG_ERR_MINTEMP_BED "Err: MINTEMP BED"
#define MSG_ERR_Z_HOMING "G28 Z Forbidden"
#define MSG_HALTED "PRINTER HALTED"
#define MSG_PLEASE_RESET "Please reset"
#define MSG_SHORT_DAY "d" // One character only
#define MSG_SHORT_HOUR "h" // One character only
#define MSG_SHORT_MINUTE "m" // One character only
#define MSG_HEATING "Heating..."
#define MSG_HEATING_COMPLETE "Heating done."
#define MSG_BED_HEATING "Bed Heating."
#define MSG_BED_DONE "Bed done."
#define MSG_DELTA_CALIBRATE "Делта Калибровка"
#define MSG_DELTA_CALIBRATE_X "Калибровка X"
#define MSG_DELTA_CALIBRATE_Y "Калибровка Y"
#define MSG_DELTA_CALIBRATE_Z "Калибровка Z"
#define MSG_DELTA_CALIBRATE_CENTER "Калибровка Център"
#define MSG_INFO_MENU "About Printer"
#define MSG_INFO_PRINTER_MENU "Printer Info"
#define MSG_INFO_STATS_MENU "Printer Stats"
#define MSG_INFO_BOARD_MENU "Board Info"
#define MSG_INFO_THERMISTOR_MENU "Thermistors"
#define MSG_INFO_EXTRUDERS "Extruders"
#define MSG_INFO_BAUDRATE "Baud"
#define MSG_INFO_PROTOCOL "Protocol"
#define MSG_LIGHTS_ON "Case light on"
#define MSG_LIGHTS_OFF "Case light off"
#if LCD_WIDTH >= 20
#define MSG_INFO_PRINT_COUNT "Print Count"
#define MSG_INFO_COMPLETED_PRINTS "Completed"
#define MSG_INFO_PRINT_TIME "Total print time"
#define MSG_INFO_PRINT_LONGEST "Longest job time"
#define MSG_INFO_PRINT_FILAMENT "Extruded total"
#else
#define MSG_INFO_PRINT_COUNT "Prints"
#define MSG_INFO_COMPLETED_PRINTS "Completed"
#define MSG_INFO_PRINT_TIME "Total"
#define MSG_INFO_PRINT_LONGEST "Longest"
#define MSG_INFO_PRINT_FILAMENT "Extruded"
#endif
#define MSG_INFO_MIN_TEMP "Min Temp"
#define MSG_INFO_MAX_TEMP "Max Temp"
#define MSG_INFO_PSU "Power Supply"
#define MSG_DRIVE_STRENGTH "Drive Strength"
#define MSG_DAC_PERCENT "Driver %"
#define MSG_DAC_EEPROM_WRITE "DAC EEPROM Write"
#define MSG_FILAMENT_CHANGE_HEADER "CHANGE FILAMENT"
#define MSG_FILAMENT_CHANGE_OPTION_HEADER "CHANGE OPTIONS:"
#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "Extrude more"
#define MSG_FILAMENT_CHANGE_OPTION_RESUME "Resume print"
#if LCD_HEIGHT >= 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Wait for start"
#define MSG_FILAMENT_CHANGE_INIT_2 "of the filament"
#define MSG_FILAMENT_CHANGE_INIT_3 "change"
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Wait for"
#define MSG_FILAMENT_CHANGE_UNLOAD_2 "filament unload"
#define MSG_FILAMENT_CHANGE_UNLOAD_3 ""
#define MSG_FILAMENT_CHANGE_INSERT_1 "Insert filament"
#define MSG_FILAMENT_CHANGE_INSERT_2 "and press button"
#define MSG_FILAMENT_CHANGE_INSERT_3 "to continue..."
#define MSG_FILAMENT_CHANGE_LOAD_1 "Wait for"
#define MSG_FILAMENT_CHANGE_LOAD_2 "filament load"
#define MSG_FILAMENT_CHANGE_LOAD_3 ""
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Wait for"
#define MSG_FILAMENT_CHANGE_EXTRUDE_2 "filament extrude"
#define MSG_FILAMENT_CHANGE_EXTRUDE_3 ""
#define MSG_FILAMENT_CHANGE_RESUME_1 "Wait for print"
#define MSG_FILAMENT_CHANGE_RESUME_2 "to resume"
#define MSG_FILAMENT_CHANGE_RESUME_3 ""
#else // LCD_HEIGHT < 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Please wait..."
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Ejecting..."
#define MSG_FILAMENT_CHANGE_INSERT_1 "Insert and Click"
#define MSG_FILAMENT_CHANGE_LOAD_1 "Loading..."
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Extruding..."
#define MSG_FILAMENT_CHANGE_RESUME_1 "Resuming..."
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_BG_H

View File

@@ -31,8 +31,6 @@
#define LANGUAGE_CA_H
#define MAPPER_C2C3 // because of "ó"
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " preparada."
@@ -89,14 +87,11 @@
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_ACC "Accel"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "

View File

@@ -29,6 +29,7 @@
*/
#ifndef LANGUAGE_CN_H
#define LANGUAGE_CN_H
#define DISPLAY_CHARSET_ISO10646_CN
#define WELCOME_MSG "\xa4\xa5\xa6\xa7"
@@ -86,14 +87,11 @@
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_ACC "Accel"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "

View File

@@ -34,8 +34,6 @@
#ifndef LANGUAGE_CZ_H
#define LANGUAGE_CZ_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " pripraven."
@@ -67,10 +65,6 @@
#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 " Vse"
#define MSG_PREHEAT_2_BEDONLY MSG_PREHEAT_2 " Podloz"
#define MSG_PREHEAT_2_SETTINGS MSG_PREHEAT_2 " Nast"
#define MSG_H1 "1"
#define MSG_H2 "2"
#define MSG_H3 "3"
#define MSG_H4 "4"
#define MSG_COOLDOWN "Zchladit"
#define MSG_SWITCH_PS_ON "Zapnout napajeni"
#define MSG_SWITCH_PS_OFF "Vypnout napajeni"
@@ -82,20 +76,12 @@
#define MSG_MOVE_Y "Posunout Y"
#define MSG_MOVE_Z "Posunout Z"
#define MSG_MOVE_E "Extruder"
#define MSG_MOVE_E1 "1"
#define MSG_MOVE_E2 "2"
#define MSG_MOVE_E3 "3"
#define MSG_MOVE_E4 "4"
#define MSG_MOVE_01MM "Posunout o 0,1mm"
#define MSG_MOVE_1MM "Posunout o 1mm"
#define MSG_MOVE_10MM "Posunout o 10mm"
#define MSG_SPEED "Rychlost"
#define MSG_BED_Z "Vyska podl."
#define MSG_NOZZLE "Tryska"
#define MSG_N1 " 1"
#define MSG_N2 " 2"
#define MSG_N3 " 3"
#define MSG_N4 " 4"
#define MSG_BED "Podlozka"
#define MSG_FAN_SPEED "Rychlost vent."
#define MSG_FLOW "Prutok"
@@ -111,19 +97,12 @@
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_SELECT "Vybrat"
#define MSG_E1 " E1"
#define MSG_E2 " E2"
#define MSG_E3 " E3"
#define MSG_E4 " E4"
#define MSG_ACC "Zrychl"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "
@@ -138,10 +117,6 @@
#define MSG_VOLUMETRIC "Filament"
#define MSG_VOLUMETRIC_ENABLED "E na mm3"
#define MSG_FILAMENT_DIAM "Fil. Prum."
#define MSG_DIAM_E1 " 1"
#define MSG_DIAM_E2 " 2"
#define MSG_DIAM_E3 " 3"
#define MSG_DIAM_E4 " 4"
#define MSG_CONTRAST "Kontrast LCD"
#define MSG_STORE_EPROM "Ulozit nastaveni"
#define MSG_LOAD_EPROM "Nacist nastaveni"
@@ -174,6 +149,8 @@
#define MSG_INIT_SDCARD "Nacist SD kartu"
#define MSG_CNG_SDCARD "Vymenit SD kartu"
#define MSG_ZPROBE_OUT "Sonda Z mimo podl"
#define MSG_BLTOUCH_SELFTEST "BLTouch Self-Test"
#define MSG_BLTOUCH_RESET "BLTouch Reset"
#define MSG_HOME "Domu" // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST
#define MSG_FIRST "prvni"
#define MSG_ZPROBE_ZOFFSET "Z ofset"
@@ -188,6 +165,7 @@
#define MSG_ERR_MINTEMP "NIZKA TEPLOTA"
#define MSG_ERR_MAXTEMP_BED "VYS. TEPL. PODL."
#define MSG_ERR_MINTEMP_BED "NIZ. TEPL. PODL."
#define MSG_ERR_Z_HOMING "G28 Z ZAKAZANO"
#define MSG_HALTED "TISK. ZASTAVENA"
#define MSG_PLEASE_RESET "Provedte reset"
#define MSG_SHORT_DAY "d"
@@ -210,7 +188,9 @@
#define MSG_INFO_EXTRUDERS "Extrudery"
#define MSG_INFO_BAUDRATE "Rychlost"
#define MSG_INFO_PROTOCOL "Protokol"
#if LCD_WIDTH > 19
#define MSG_LIGHTS_ON "Osvetleni Zap"
#define MSG_LIGHTS_OFF "Osvetleni Vyp"
#if LCD_WIDTH >= 20
#define MSG_INFO_PRINT_COUNT "Pocet tisku"
#define MSG_INFO_COMPLETED_PRINTS "Dokonceno"
#define MSG_INFO_PRINT_TIME "Celkovy cas"
@@ -226,6 +206,9 @@
#define MSG_INFO_MIN_TEMP "Teplota min"
#define MSG_INFO_MAX_TEMP "Teplota max"
#define MSG_INFO_PSU "Nap. zdroj"
#define MSG_DRIVE_STRENGTH "Buzeni motoru"
#define MSG_DAC_PERCENT "Motor %"
#define MSG_DAC_EEPROM_WRITE "Ulozit do EEPROM"
#define MSG_FILAMENT_CHANGE_HEADER "VYMENA FILAMENTU"
#define MSG_FILAMENT_CHANGE_OPTION_HEADER "CO DAL?"

View File

@@ -31,8 +31,6 @@
#define LANGUAGE_DA_H
#define MAPPER_C2C3
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " er klar"
@@ -47,12 +45,12 @@
#define MSG_AUTO_HOME_Y "Home Y"
#define MSG_AUTO_HOME_Z "Home Z"
#define MSG_LEVEL_BED_HOMING "Homing XYZ"
#define MSG_LEVEL_BED_WAITING "Tryk for at starte bed level"
#define MSG_LEVEL_BED_WAITING "Klik når du er klar"
#define MSG_LEVEL_BED_NEXT_POINT "Næste punkt"
#define MSG_LEVEL_BED_DONE "Bed level er færdig!"
#define MSG_LEVEL_BED_CANCEL "Annuller bed level"
#define MSG_SET_HOME_OFFSETS "Sæt forskyding af home"
#define MSG_HOME_OFFSETS_APPLIED "Forskydninger af home pos. er tilføjet"
#define MSG_SET_HOME_OFFSETS "Sæt forsk. af home"
#define MSG_HOME_OFFSETS_APPLIED "Forsk. er nu aktiv"
#define MSG_SET_ORIGIN "Sæt origin"
#define MSG_PREHEAT_1 "Forvarm PLA"
#define MSG_PREHEAT_1_N "Forvarm PLA "
@@ -64,10 +62,6 @@
#define MSG_PREHEAT_2_ALL "Forvarm ABS Alle"
#define MSG_PREHEAT_2_BEDONLY "Forvarm ABS Bed"
#define MSG_PREHEAT_2_SETTINGS "Forvarm ABS conf"
#define MSG_H1 "1"
#define MSG_H2 "2"
#define MSG_H3 "3"
#define MSG_H4 "4"
#define MSG_COOLDOWN "Afkøl"
#define MSG_SWITCH_PS_ON "Slå strøm til"
#define MSG_SWITCH_PS_OFF "Slå strøm fra"
@@ -79,20 +73,13 @@
#define MSG_MOVE_Y "Flyt Y"
#define MSG_MOVE_Z "Flyt Z"
#define MSG_MOVE_E "Extruder"
#define MSG_MOVE_E1 "1"
#define MSG_MOVE_E2 "2"
#define MSG_MOVE_E3 "3"
#define MSG_MOVE_E4 "4"
#define MSG_MOVE_01MM "Flyt 0.1mm"
#define MSG_MOVE_1MM "Flyt 1mm"
#define MSG_MOVE_10MM "Flyt 10mm"
#define MSG_SPEED "Hastighed"
#define MSG_BED_Z "Plade Z"
#define MSG_NOZZLE "Dyse"
#define MSG_N1 " 1"
#define MSG_N2 " 2"
#define MSG_N3 " 3"
#define MSG_N4 " 4"
#define MSG_BED "Plade"
#define MSG_FAN_SPEED "Blæser hastighed"
#define MSG_FLOW "Flow"
@@ -107,19 +94,13 @@
#define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_E1 " E1"
#define MSG_E2 " E2"
#define MSG_E3 " E3"
#define MSG_E4 " E4"
#define MSG_SELECT "Vælg"
#define MSG_ACC "Accel"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "
@@ -132,12 +113,8 @@
#define MSG_TEMPERATURE "Temperatur"
#define MSG_MOTION "Bevægelse"
#define MSG_VOLUMETRIC "Filament"
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
#define MSG_VOLUMETRIC_ENABLED "E i mm3"
#define MSG_FILAMENT_DIAM "Fil. Dia."
#define MSG_DIAM_E1 " 1"
#define MSG_DIAM_E2 " 2"
#define MSG_DIAM_E3 " 3"
#define MSG_DIAM_E4 " 4"
#define MSG_CONTRAST "LCD kontrast"
#define MSG_STORE_EPROM "Gem i EEPROM"
#define MSG_LOAD_EPROM "Hent fra EEPROM"
@@ -163,27 +140,35 @@
#define MSG_CONTROL_RETRACTF "Tilbagetræk V"
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm"
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
#define MSG_CONTROL_RETRACT_RECOVER_SWAP "S UnRet+mm"
#define MSG_CONTROL_RETRACT_RECOVER_SWAP "Skift UnRet+mm"
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet V"
#define MSG_AUTORETRACT "AutoRetr."
#define MSG_FILAMENTCHANGE "Skift filament"
#define MSG_INIT_SDCARD "Init. SD card"
#define MSG_CNG_SDCARD "Skift SD kort"
#define MSG_ZPROBE_OUT "Probe udenfor plade"
#define MSG_BLTOUCH_SELFTEST "BLTouch Selv-Test"
#define MSG_BLTOUCH_RESET "Reset BLTouch"
#define MSG_HOME "Home" // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST
#define MSG_FIRST "first"
#define MSG_FIRST "først"
#define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_Y "Babystep Y"
#define MSG_BABYSTEP_Z "Babystep Z"
#define MSG_ENDSTOP_ABORT "Endstop abort"
#define MSG_HEATING_FAILED_LCD "Opvarmning mislykkedes"
#define MSG_HEATING_FAILED_LCD "Opvarmning fejlet"
#define MSG_ERR_REDUNDANT_TEMP "Fejl: reserve temp"
#define MSG_THERMAL_RUNAWAY "Temp løber løbsk"
#define MSG_ERR_MAXTEMP "Fejl: Maks temp"
#define MSG_ERR_MINTEMP "Fejl: Min temp"
#define MSG_ERR_MAXTEMP_BED "Fejl: Maks Plsde temp"
#define MSG_ERR_MAXTEMP_BED "Fejl: Maks Plade temp"
#define MSG_ERR_MINTEMP_BED "Fejl: Min Plade temp"
#define MSG_ERR_Z_HOMING "G28 Z Forbudt"
#define MSG_HALTED "PRINTER STOPPET"
#define MSG_PLEASE_RESET "Reset Venligst"
#define MSG_SHORT_DAY "d" // Kun et bogstav
#define MSG_SHORT_HOUR "h" // Kun et bogstav
#define MSG_SHORT_MINUTE "m" // Kun et bogstav
#define MSG_HEATING "Opvarmer..."
#define MSG_HEATING_COMPLETE "Opvarmet"
#define MSG_BED_HEATING "Opvarmer plade"
@@ -194,4 +179,63 @@
#define MSG_DELTA_CALIBRATE_Z "Kalibrer Z"
#define MSG_DELTA_CALIBRATE_CENTER "Kalibrerings Center"
#define MSG_INFO_MENU "Om Printer"
#define MSG_INFO_PRINTER_MENU "Printer Info"
#define MSG_INFO_STATS_MENU "Printer Stats"
#define MSG_INFO_BOARD_MENU "Kort Info"
#define MSG_INFO_THERMISTOR_MENU "Thermistors"
#define MSG_INFO_EXTRUDERS "Extruders"
#define MSG_INFO_BAUDRATE "Baud"
#define MSG_INFO_PROTOCOL "Protocol"
#if LCD_WIDTH >= 20
#define MSG_INFO_PRINT_COUNT "Ant. Prints"
#define MSG_INFO_COMPLETED_PRINTS "Færdige"
#define MSG_INFO_PRINT_TIME "Total print tid"
#define MSG_INFO_PRINT_LONGEST "Længste print"
#define MSG_INFO_PRINT_FILAMENT "Total Extruderet"
#else
#define MSG_INFO_PRINT_COUNT "Prints"
#define MSG_INFO_COMPLETED_PRINTS "Færdige"
#define MSG_INFO_PRINT_TIME "Total"
#define MSG_INFO_PRINT_LONGEST "Længste"
#define MSG_INFO_PRINT_FILAMENT "Extruderet"
#endif
#define MSG_INFO_MIN_TEMP "Min Temp"
#define MSG_INFO_MAX_TEMP "Max Temp"
#define MSG_INFO_PSU "Strømfors."
#define MSG_DRIVE_STRENGTH "Driv Styrke"
#define MSG_DAC_PERCENT "Driv %"
#define MSG_DAC_EEPROM_WRITE "DAC EEPROM Skriv"
#define MSG_FILAMENT_CHANGE_HEADER "SKIFT FILAMENT"
#define MSG_FILAMENT_CHANGE_OPTION_HEADER "Skift muligheder:"
#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "Extruder mere"
#define MSG_FILAMENT_CHANGE_OPTION_RESUME "Forsæt print"
#if LCD_HEIGHT >= 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Vent på start"
#define MSG_FILAMENT_CHANGE_INIT_2 "af filament"
#define MSG_FILAMENT_CHANGE_INIT_3 "skift"
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Vent på"
#define MSG_FILAMENT_CHANGE_UNLOAD_2 "filament udskyd."
#define MSG_FILAMENT_CHANGE_INSERT_1 "Indsæt filament"
#define MSG_FILAMENT_CHANGE_INSERT_2 "og tryk på knap"
#define MSG_FILAMENT_CHANGE_INSERT_3 "for at fortsætte..."
#define MSG_FILAMENT_CHANGE_LOAD_1 "Vent på"
#define MSG_FILAMENT_CHANGE_LOAD_2 "filament indtag"
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Vent på"
#define MSG_FILAMENT_CHANGE_EXTRUDE_2 "filament extrudering"
#define MSG_FILAMENT_CHANGE_RESUME_1 "Vent på at print"
#define MSG_FILAMENT_CHANGE_RESUME_2 "fortsætter"
#else // LCD_HEIGHT < 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Vent venligst..."
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Udskyder..."
#define MSG_FILAMENT_CHANGE_INSERT_1 "Indsæt og klik"
#define MSG_FILAMENT_CHANGE_LOAD_1 "Indtager..."
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Extrudere..."
#define MSG_FILAMENT_CHANGE_RESUME_1 "Fortsætter..."
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_DA_H

View File

@@ -31,23 +31,26 @@
#define LANGUAGE_DE_H
#define MAPPER_C2C3
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " bereit"
#define MSG_SD_INSERTED "SD-Karte erkannt"
#define MSG_SD_REMOVED "SD-Karte entfernt"
#define MSG_LCD_ENDSTOPS "Endstopp" // Max length 8 characters
#define MSG_MAIN "Hauptmenü"
#define MSG_AUTOSTART "Autostart"
#define MSG_DISABLE_STEPPERS "Motoren aus" // M84
#define MSG_DISABLE_STEPPERS "Motoren deaktivieren" // M84
#define MSG_AUTO_HOME "Home" // G28
#define MSG_AUTO_HOME_X "Home X"
#define MSG_AUTO_HOME_Y "Home Y"
#define MSG_AUTO_HOME_Z "Home Z"
#define MSG_LEVEL_BED_HOMING "Homing XYZ"
#define MSG_LEVEL_BED_WAITING "Klick für Start"
#define MSG_LEVEL_BED_NEXT_POINT "Nächste Koordinate"
#define MSG_LEVEL_BED_DONE "Fertig"
#define MSG_LEVEL_BED_CANCEL "Abbruch"
#define MSG_SET_HOME_OFFSETS "Setze Homeoffsets"
#define MSG_HOME_OFFSETS_APPLIED "Offsets aktiv"
#define MSG_SET_HOME_OFFSETS "Setze Homeversatz"
#define MSG_HOME_OFFSETS_APPLIED "Homeversatz aktiv"
#define MSG_SET_ORIGIN "Setze Nullpunkt" //"G92 X0 Y0 Z0" commented out in ultralcd.cpp
#define MSG_PREHEAT_1 "Vorwärmen PLA"
#define MSG_PREHEAT_1_N "Vorwärmen PLA "
@@ -69,10 +72,10 @@
#define MSG_MOVE_X "X"
#define MSG_MOVE_Y "Y"
#define MSG_MOVE_Z "Z"
#define MSG_MOVE_E "E"
#define MSG_MOVE_01MM " 0.1 mm"
#define MSG_MOVE_1MM " 1.0 mm"
#define MSG_MOVE_10MM "10.0 mm"
#define MSG_MOVE_E "Extruder "
#define MSG_MOVE_01MM " 0,1 mm"
#define MSG_MOVE_1MM " 1,0 mm"
#define MSG_MOVE_10MM "10,0 mm"
#define MSG_SPEED "Geschw."
#define MSG_BED_Z "Bett Z"
#define MSG_NOZZLE "Düse"
@@ -90,15 +93,13 @@
#define MSG_PID_I "PID I"
#define MSG_PID_D "PID D"
#define MSG_PID_C "PID C"
#define MSG_SELECT "Auswählen"
#define MSG_ACC "A"
#define MSG_VXY_JERK "V XY Jerk"
#define MSG_VZ_JERK "V Z Jerk"
#define MSG_VE_JERK "V E Jerk"
#define MSG_VX_JERK "V X Jerk"
#define MSG_VY_JERK "V Y Jerk"
#define MSG_VZ_JERK "V Z Jerk"
#define MSG_VE_JERK "V E Jerk"
#define MSG_VMAX "V max " // space by purpose
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "V min"
#define MSG_VTRAV_MIN "V min Leerfahrt"
#define MSG_AMAX "A max " // space by purpose
@@ -131,7 +132,7 @@
#define MSG_RESUMING "Druckfortsetzung"
#define MSG_PRINT_ABORTED "Druck abgebrochen"
#define MSG_NO_MOVE "Motoren eingeschaltet"
#define MSG_KILLED "KILLED"
#define MSG_KILLED "ABGEBROCHEN"
#define MSG_STOPPED "ANGEHALTEN"
#define MSG_CONTROL_RETRACT "Retract mm"
#define MSG_CONTROL_RETRACT_SWAP "Wechs. Retract mm"
@@ -145,13 +146,15 @@
#define MSG_INIT_SDCARD "SD-Karte erkennen" // Manually initialize the SD-card via user interface
#define MSG_CNG_SDCARD "SD-Karte getauscht" // SD-card changed by user. For machines with no autocarddetect. Both send "M21"
#define MSG_ZPROBE_OUT "Sensor ausserhalb"
#define MSG_BLTOUCH_SELFTEST "BLTouch Test"
#define MSG_BLTOUCH_RESET "BLTouch Reset"
#define MSG_HOME "Vorher" // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST
#define MSG_FIRST "homen"
#define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_ZPROBE_ZOFFSET "Z Versatz"
#define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_Y "Babystep Y"
#define MSG_BABYSTEP_Z "Babystep Z"
#define MSG_ENDSTOP_ABORT "Endstop-Abbr. ein"
#define MSG_ENDSTOP_ABORT "Endstopp-Abbr. ein"
#define MSG_HEATING_FAILED_LCD "HEIZEN FEHLGESCHLAGEN"
#define MSG_ERR_REDUNDANT_TEMP "REDUND. TEMPERATURABWEICHUNG"
#define MSG_THERMAL_RUNAWAY LCD_STR_THERMOMETER " NICHT ERREICHT"
@@ -159,9 +162,15 @@
#define MSG_ERR_MINTEMP LCD_STR_THERMOMETER " UNTERSCHRITTEN"
#define MSG_ERR_MAXTEMP_BED "BETT " LCD_STR_THERMOMETER " ÜBERSCHRITTEN"
#define MSG_ERR_MINTEMP_BED "BETT " LCD_STR_THERMOMETER " UNTERSCHRITTEN"
#define MSG_HEATING "Aufheizen..."
#define MSG_HEATING_COMPLETE "Aufgeheizt"
#define MSG_BED_HEATING "Bett aufheizen"
#define MSG_ERR_Z_HOMING "G28 Z verboten"
#define MSG_HALTED "DRUCKER STOPP"
#define MSG_PLEASE_RESET "Bitte Resetten"
#define MSG_SHORT_DAY "t" // One character only
#define MSG_SHORT_HOUR "h" // One character only
#define MSG_SHORT_MINUTE "m" // One character only
#define MSG_HEATING "Extr. heizt..."
#define MSG_HEATING_COMPLETE "Extr. aufgeheizt"
#define MSG_BED_HEATING "Bett heizt..."
#define MSG_BED_DONE "Bett aufgeheizt"
#define MSG_DELTA_CALIBRATE "Delta kalibrieren"
#define MSG_DELTA_CALIBRATE_X "Kalibriere X"
@@ -171,26 +180,36 @@
#define MSG_INFO_MENU "Über den Drucker"
#define MSG_INFO_PRINTER_MENU "Drucker Info"
#define MSG_INFO_STATS_MENU "Drucker Stats"
#define MSG_INFO_STATS_MENU "Drucker Stat."
#define MSG_INFO_BOARD_MENU "Board Info"
#define MSG_INFO_THERMISTOR_MENU "Thermistors"
#define MSG_INFO_EXTRUDERS "Extruders"
#define MSG_INFO_BAUDRATE "Baud"
#define MSG_INFO_PROTOCOL "Protokol"
#define MSG_INFO_PROTOCOL "Protokoll"
#define MSG_LIGHTS_ON "Gehäuse Licht an"
#define MSG_LIGHTS_OFF "Gehäuse Licht aus"
#if LCD_WIDTH > 19
#define MSG_INFO_PRINT_COUNT "Gesamte Drucke "
#define MSG_INFO_COMPLETED_PRINTS "Beendete Drucke "
#if LCD_WIDTH >= 20
#define MSG_INFO_PRINT_COUNT "Gesamte Drucke"
#define MSG_INFO_COMPLETED_PRINTS "Beendete Drucke"
#define MSG_INFO_PRINT_TIME "Gesamte Druckzeit"
#define MSG_INFO_PRINT_LONGEST "Längster Druckjob"
#define MSG_INFO_PRINT_FILAMENT "Gesamt Extrudiert"
#else
#define MSG_INFO_PRINT_COUNT "Prints "
#define MSG_INFO_COMPLETED_PRINTS "Completed"
#define MSG_INFO_PRINT_TIME "Duration "
#define MSG_INFO_PRINT_COUNT "Drucke"
#define MSG_INFO_COMPLETED_PRINTS "Komplett"
#define MSG_INFO_PRINT_TIME "Gesamt "
#define MSG_INFO_PRINT_LONGEST "Längster"
#define MSG_INFO_PRINT_FILAMENT "Extrud."
#endif
#define MSG_INFO_MIN_TEMP "Min Temp"
#define MSG_INFO_MAX_TEMP "Max Temp"
#define MSG_INFO_PSU "Stromversorgung"
#define MSG_DRIVE_STRENGTH "Motorströme"
#define MSG_DAC_PERCENT "Treiber %"
#define MSG_DAC_EEPROM_WRITE "Werte speichern"
#define MSG_FILAMENT_CHANGE_HEADER "ÄNDERE FILAMENT"
#define MSG_FILAMENT_CHANGE_OPTION_HEADER "ÄNDERE OPTIONEN:"
#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "Extrude mehr"
@@ -198,29 +217,29 @@
#if LCD_HEIGHT >= 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Warte auf den"
#define MSG_FILAMENT_CHANGE_INIT_2 "Start zum "
#define MSG_FILAMENT_CHANGE_INIT_3 "Filament wechsel"
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Warte auf das"
#define MSG_FILAMENT_CHANGE_UNLOAD_2 "herrausnehmen"
#define MSG_FILAMENT_CHANGE_INIT_2 "Start des "
#define MSG_FILAMENT_CHANGE_INIT_3 "Filamentwechsels"
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Warte auf"
#define MSG_FILAMENT_CHANGE_UNLOAD_2 "Herausnahme"
#define MSG_FILAMENT_CHANGE_UNLOAD_3 "des Filaments"
#define MSG_FILAMENT_CHANGE_INSERT_1 "Fädel Filament"
#define MSG_FILAMENT_CHANGE_INSERT_2 "ein und drücke"
#define MSG_FILAMENT_CHANGE_INSERT_3 "den Knopf..."
#define MSG_FILAMENT_CHANGE_LOAD_1 "Warte auf das"
#define MSG_FILAMENT_CHANGE_LOAD_2 "laden des"
#define MSG_FILAMENT_CHANGE_INSERT_1 "Filament einlegen"
#define MSG_FILAMENT_CHANGE_INSERT_2 "und Knopf"
#define MSG_FILAMENT_CHANGE_INSERT_3 "drücken..."
#define MSG_FILAMENT_CHANGE_LOAD_1 "Warte auf"
#define MSG_FILAMENT_CHANGE_LOAD_2 "Laden des"
#define MSG_FILAMENT_CHANGE_LOAD_3 "Filaments"
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Warte auf das"
#define MSG_FILAMENT_CHANGE_EXTRUDE_2 "Extruden des"
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Warte auf"
#define MSG_FILAMENT_CHANGE_EXTRUDE_2 "Extrusion des"
#define MSG_FILAMENT_CHANGE_EXTRUDE_3 "Filaments"
#define MSG_FILAMENT_CHANGE_RESUME_1 "Warte auf das"
#define MSG_FILAMENT_CHANGE_RESUME_2 "fortfahren des"
#define MSG_FILAMENT_CHANGE_RESUME_1 "Warte auf"
#define MSG_FILAMENT_CHANGE_RESUME_2 "Fortsetzung des"
#define MSG_FILAMENT_CHANGE_RESUME_3 "Druckes"
#else // LCD_HEIGHT < 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Bitte warten..."
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Auswerfen..."
#define MSG_FILAMENT_CHANGE_INSERT_1 "Laden und Klick"
#define MSG_FILAMENT_CHANGE_LOAD_1 "Laden..."
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Extruden..."
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Extrudieren..."
#define MSG_FILAMENT_CHANGE_RESUME_1 "Weitermachen..."
#endif // LCD_HEIGHT < 4

View File

@@ -30,11 +30,8 @@
#ifndef LANGUAGE_EL_GR_H
#define LANGUAGE_EL_GR_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
//#define MAPPER_CECF
//#define DISPLAY_CHARSET_ISO10646_GREEK
#define MAPPER_CECF
#define DISPLAY_CHARSET_ISO10646_GREEK
#define WELCOME_MSG MACHINE_NAME " έτοιμο."
#define MSG_SD_INSERTED "Εισαγωγή κάρτας"
@@ -65,10 +62,6 @@
#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 " όλα"
#define MSG_PREHEAT_2_BEDONLY MSG_PREHEAT_2 " Bed"
#define MSG_PREHEAT_2_SETTINGS MSG_PREHEAT_2 " επιβεβαίωση"
#define MSG_H1 "1"
#define MSG_H2 "2"
#define MSG_H3 "3"
#define MSG_H4 "4"
#define MSG_COOLDOWN "Μειωση θερμοκρασιας"
#define MSG_SWITCH_PS_ON "Ενεργοποίηση"
#define MSG_SWITCH_PS_OFF "Απενεργοποίηση"
@@ -80,20 +73,12 @@
#define MSG_MOVE_Y "Μετακίνηση Y"
#define MSG_MOVE_Z "Μετακίνηση Z"
#define MSG_MOVE_E "Εξωθητήρας"
#define MSG_MOVE_E1 "1"
#define MSG_MOVE_E2 "2"
#define MSG_MOVE_E3 "3"
#define MSG_MOVE_E4 "4"
#define MSG_MOVE_01MM "Μετακίνηση 0,1 μμ"
#define MSG_MOVE_1MM "Μετακίνηση 1 μμ"
#define MSG_MOVE_10MM "Μετακίνηση 10 μμ"
#define MSG_SPEED "Ταχύτητα"
#define MSG_BED_Z "Κλίνη Z"
#define MSG_NOZZLE "Ακροφύσιο"
#define MSG_N1 " 1"
#define MSG_N2 " 2"
#define MSG_N3 " 3"
#define MSG_N4 " 4"
#define MSG_BED "Κλίνη"
#define MSG_FAN_SPEED "Ταχύτητα ανεμιστήρα"
#define MSG_FLOW "Ροή"
@@ -108,19 +93,12 @@
#define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_E1 " E1"
#define MSG_E2 " E2"
#define MSG_E3 " E3"
#define MSG_E4 " E4"
#define MSG_ACC "Επιτάχυνση"
#define MSG_VXY_JERK "Vαντίδραση xy"
#define MSG_VX_JERK "Vαντίδραση x"
#define MSG_VY_JERK "Vαντίδραση y"
#define MSG_VZ_JERK "Vαντίδραση z"
#define MSG_VE_JERK "Vαντίδραση e"
#define MSG_VMAX "Vμεγ "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vελαχ"
#define MSG_VTRAV_MIN "Vελάχ. μετατόπιση"
#define MSG_AMAX "Aμεγ "
@@ -135,10 +113,6 @@
#define MSG_VOLUMETRIC "Νήμα"
#define MSG_VOLUMETRIC_ENABLED "Ε σε μμ3"
#define MSG_FILAMENT_DIAM "Διάμετρος νήματος"
#define MSG_DIAM_E1 " 1"
#define MSG_DIAM_E2 " 2"
#define MSG_DIAM_E3 " 3"
#define MSG_DIAM_E4 " 4"
#define MSG_CONTRAST "Κοντράστ LCD"
#define MSG_STORE_EPROM "Αποθήκευση"
#define MSG_LOAD_EPROM "Φόρτωση"

View File

@@ -30,9 +30,6 @@
#ifndef LANGUAGE_EL_H
#define LANGUAGE_EL_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define MAPPER_CECF
#define DISPLAY_CHARSET_ISO10646_GREEK
@@ -65,10 +62,6 @@
#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 " όλα"
#define MSG_PREHEAT_2_BEDONLY MSG_PREHEAT_2 " bed" //SHORTEN
#define MSG_PREHEAT_2_SETTINGS MSG_PREHEAT_2 " επιβεβαίωση" //SHORTEN
#define MSG_H1 "1"
#define MSG_H2 "2"
#define MSG_H3 "3"
#define MSG_H4 "4"
#define MSG_COOLDOWN "Μειωση θερμοκρασιας"
#define MSG_SWITCH_PS_ON "Ενεργοποίηση"
#define MSG_SWITCH_PS_OFF "Απενεργοποίηση"
@@ -80,20 +73,12 @@
#define MSG_MOVE_Y "Μετακίνηση Y"
#define MSG_MOVE_Z "Μετακίνηση Z"
#define MSG_MOVE_E "Εξωθητήρας"
#define MSG_MOVE_E1 "1"
#define MSG_MOVE_E2 "2"
#define MSG_MOVE_E3 "3"
#define MSG_MOVE_E4 "4"
#define MSG_MOVE_01MM "Μετακίνηση 0,1μμ"
#define MSG_MOVE_1MM "Μετακίνηση 1μμ"
#define MSG_MOVE_10MM "Μετακίνηση 10μμ"
#define MSG_SPEED "Ταχύτητα"
#define MSG_BED_Z "Επ. Εκτύπωσης Z"
#define MSG_NOZZLE "Ακροφύσιο"
#define MSG_N1 " 1"
#define MSG_N2 " 2"
#define MSG_N3 " 3"
#define MSG_N4 " 4"
#define MSG_BED "Κλίνη"
#define MSG_FAN_SPEED "Ταχύτητα ανεμιστήρα"
#define MSG_FLOW "Ροή"
@@ -108,19 +93,12 @@
#define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_E1 " E1"
#define MSG_E2 " E2"
#define MSG_E3 " E3"
#define MSG_E4 " E4"
#define MSG_ACC "Επιτάχυνση"
#define MSG_VXY_JERK "Vαντίδραση xy"
#define MSG_VX_JERK "Vαντίδραση x"
#define MSG_VY_JERK "Vαντίδραση y"
#define MSG_VZ_JERK "Vαντίδραση z"
#define MSG_VE_JERK "Vαντίδραση e"
#define MSG_VMAX "V Μέγιστο"
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "V Ελάχιστο"
#define MSG_VTRAV_MIN "Vελάχ. μετατόπιση"
#define MSG_AMAX "Aμεγ "
@@ -135,10 +113,6 @@
#define MSG_VOLUMETRIC "Νήμα"
#define MSG_VOLUMETRIC_ENABLED "Ε σε μμ3"
#define MSG_FILAMENT_DIAM "Διάμετρος νήματος"
#define MSG_DIAM_E1 " 1"
#define MSG_DIAM_E2 " 2"
#define MSG_DIAM_E3 " 3"
#define MSG_DIAM_E4 " 4"
#define MSG_CONTRAST "Κοντράστ LCD"
#define MSG_STORE_EPROM "Αποθήκευση"
#define MSG_LOAD_EPROM "Φόρτωση"
@@ -206,7 +180,7 @@
#define MSG_INFO_BAUDRATE "Baud"
#define MSG_INFO_PROTOCOL "Protocol"
#if LCD_WIDTH > 19
#if LCD_WIDTH >= 20
#define MSG_INFO_PRINT_COUNT "Print Count"
#define MSG_INFO_COMPLETED_PRINTS "Completed "
#define MSG_INFO_PRINT_TIME "Total Time "

View File

@@ -30,11 +30,6 @@
#ifndef LANGUAGE_EN_H
#define LANGUAGE_EN_H
//#define SIMULATE_ROMFONT //Comment in to see what is seen on the character based displays
#if DISABLED(SIMULATE_ROMFONT) && DISABLED(DISPLAY_CHARSET_ISO10646_1) && DISABLED(DISPLAY_CHARSET_ISO10646_5) && DISABLED(DISPLAY_CHARSET_ISO10646_KANA) && DISABLED(DISPLAY_CHARSET_ISO10646_GREEK) && DISABLED(DISPLAY_CHARSET_ISO10646_CN)
#define DISPLAY_CHARSET_ISO10646_1 // use the better font on full graphic displays.
#endif
#ifndef WELCOME_MSG
#define WELCOME_MSG MACHINE_NAME " ready."
#endif
@@ -122,18 +117,6 @@
#ifndef MSG_PREHEAT_2_SETTINGS
#define MSG_PREHEAT_2_SETTINGS MSG_PREHEAT_2 " conf"
#endif
#ifndef MSG_H1
#define MSG_H1 "1"
#endif
#ifndef MSG_H2
#define MSG_H2 "2"
#endif
#ifndef MSG_H3
#define MSG_H3 "3"
#endif
#ifndef MSG_H4
#define MSG_H4 "4"
#endif
#ifndef MSG_COOLDOWN
#define MSG_COOLDOWN "Cooldown"
#endif
@@ -167,18 +150,6 @@
#ifndef MSG_MOVE_E
#define MSG_MOVE_E "Extruder"
#endif
#ifndef MSG_MOVE_E1
#define MSG_MOVE_E1 "1"
#endif
#ifndef MSG_MOVE_E2
#define MSG_MOVE_E2 "2"
#endif
#ifndef MSG_MOVE_E3
#define MSG_MOVE_E3 "3"
#endif
#ifndef MSG_MOVE_E4
#define MSG_MOVE_E4 "4"
#endif
#ifndef MSG_MOVE_01MM
#define MSG_MOVE_01MM "Move 0.1mm"
#endif
@@ -197,18 +168,6 @@
#ifndef MSG_NOZZLE
#define MSG_NOZZLE "Nozzle"
#endif
#ifndef MSG_N1
#define MSG_N1 " 1"
#endif
#ifndef MSG_N2
#define MSG_N2 " 2"
#endif
#ifndef MSG_N3
#define MSG_N3 " 3"
#endif
#ifndef MSG_N4
#define MSG_N4 " 4"
#endif
#ifndef MSG_BED
#define MSG_BED "Bed"
#endif
@@ -254,23 +213,14 @@
#ifndef MSG_SELECT
#define MSG_SELECT "Select"
#endif
#ifndef MSG_E1
#define MSG_E1 " E1"
#endif
#ifndef MSG_E2
#define MSG_E2 " E2"
#endif
#ifndef MSG_E3
#define MSG_E3 " E3"
#endif
#ifndef MSG_E4
#define MSG_E4 " E4"
#endif
#ifndef MSG_ACC
#define MSG_ACC "Accel"
#endif
#ifndef MSG_VXY_JERK
#define MSG_VXY_JERK "Vxy-jerk"
#ifndef MSG_VX_JERK
#define MSG_VX_JERK "Vx-jerk"
#endif
#ifndef MSG_VY_JERK
#define MSG_VY_JERK "Vy-jerk"
#endif
#ifndef MSG_VZ_JERK
#define MSG_VZ_JERK "Vz-jerk"
@@ -281,18 +231,6 @@
#ifndef MSG_VMAX
#define MSG_VMAX "Vmax "
#endif
#ifndef MSG_X
#define MSG_X "X"
#endif
#ifndef MSG_Y
#define MSG_Y "Y"
#endif
#ifndef MSG_Z
#define MSG_Z "Z"
#endif
#ifndef MSG_E
#define MSG_E "E"
#endif
#ifndef MSG_VMIN
#define MSG_VMIN "Vmin"
#endif
@@ -335,18 +273,6 @@
#ifndef MSG_FILAMENT_DIAM
#define MSG_FILAMENT_DIAM "Fil. Dia."
#endif
#ifndef MSG_DIAM_E1
#define MSG_DIAM_E1 " 1"
#endif
#ifndef MSG_DIAM_E2
#define MSG_DIAM_E2 " 2"
#endif
#ifndef MSG_DIAM_E3
#define MSG_DIAM_E3 " 3"
#endif
#ifndef MSG_DIAM_E4
#define MSG_DIAM_E4 " 4"
#endif
#ifndef MSG_CONTRAST
#define MSG_CONTRAST "LCD contrast"
#endif
@@ -443,6 +369,12 @@
#ifndef MSG_ZPROBE_OUT
#define MSG_ZPROBE_OUT "Z probe out. bed"
#endif
#ifndef MSG_BLTOUCH_SELFTEST
#define MSG_BLTOUCH_SELFTEST "BLTouch Self-Test"
#endif
#ifndef MSG_BLTOUCH_RESET
#define MSG_BLTOUCH_RESET "Reset BLTouch"
#endif
#ifndef MSG_HOME
#define MSG_HOME "Home" // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST
#endif
@@ -485,6 +417,9 @@
#ifndef MSG_ERR_MINTEMP_BED
#define MSG_ERR_MINTEMP_BED "Err: MINTEMP BED"
#endif
#ifndef MSG_ERR_Z_HOMING
#define MSG_ERR_Z_HOMING "G28 Z Forbidden"
#endif
#ifndef MSG_HALTED
#define MSG_HALTED "PRINTER HALTED"
#endif
@@ -552,8 +487,14 @@
#ifndef MSG_INFO_PROTOCOL
#define MSG_INFO_PROTOCOL "Protocol"
#endif
#ifndef MSG_LIGHTS_ON
#define MSG_LIGHTS_ON "Case light on"
#endif
#ifndef MSG_LIGHTS_OFF
#define MSG_LIGHTS_OFF "Case light off"
#endif
#if LCD_WIDTH > 19
#if LCD_WIDTH >= 20
#ifndef MSG_INFO_PRINT_COUNT
#define MSG_INFO_PRINT_COUNT "Print Count"
#endif
@@ -597,6 +538,15 @@
#define MSG_INFO_PSU "Power Supply"
#endif
#ifndef MSG_DRIVE_STRENGTH
#define MSG_DRIVE_STRENGTH "Drive Strength"
#endif
#ifndef MSG_DAC_PERCENT
#define MSG_DAC_PERCENT "Driver %"
#endif
#ifndef MSG_DAC_EEPROM_WRITE
#define MSG_DAC_EEPROM_WRITE "DAC EEPROM Write"
#endif
#ifndef MSG_FILAMENT_CHANGE_HEADER
#define MSG_FILAMENT_CHANGE_HEADER "CHANGE FILAMENT"
#endif

View File

@@ -30,8 +30,6 @@
#ifndef LANGUAGE_ES_H
#define LANGUAGE_ES_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " lista."
@@ -46,7 +44,7 @@
#define MSG_AUTO_HOME_Y "Origen Y"
#define MSG_AUTO_HOME_Z "Origen Z"
#define MSG_LEVEL_BED_HOMING "Origen XYZ"
#define MSG_LEVEL_BED_WAITING "Presione para iniciar"
#define MSG_LEVEL_BED_WAITING "Iniciar (Presione)"
#define MSG_LEVEL_BED_DONE "Nivelacion lista!"
#define MSG_LEVEL_BED_CANCEL "Cancelar"
#define MSG_SET_HOME_OFFSETS "Ajustar desfases"
@@ -62,10 +60,6 @@
#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 "Todo"
#define MSG_PREHEAT_2_BEDONLY MSG_PREHEAT_2 "Plataforma"
#define MSG_PREHEAT_2_SETTINGS MSG_PREHEAT_2 "Config"
#define MSG_H1 "1"
#define MSG_H2 "2"
#define MSG_H3 "3"
#define MSG_H4 "4"
#define MSG_COOLDOWN "Enfriar"
#define MSG_SWITCH_PS_ON "Encender"
#define MSG_SWITCH_PS_OFF "Apagar"
@@ -77,20 +71,12 @@
#define MSG_MOVE_Y "Mover Y"
#define MSG_MOVE_Z "Mover Z"
#define MSG_MOVE_E "Extrusor"
#define MSG_MOVE_E1 "1"
#define MSG_MOVE_E2 "2"
#define MSG_MOVE_E3 "3"
#define MSG_MOVE_E4 "4"
#define MSG_MOVE_01MM "Mover 0.1mm"
#define MSG_MOVE_1MM "Mover 1mm"
#define MSG_MOVE_10MM "Mover 10mm"
#define MSG_SPEED "Velocidad"
#define MSG_BED_Z "Plataforma Z"
#define MSG_NOZZLE "Boquilla"
#define MSG_N1 " 1"
#define MSG_N2 " 2"
#define MSG_N3 " 3"
#define MSG_N4 " 4"
#define MSG_BED "Plataforma"
#define MSG_FAN_SPEED "Ventilador"
#define MSG_FLOW "Flujo"
@@ -98,26 +84,19 @@
#define MSG_MIN LCD_STR_THERMOMETER " Min"
#define MSG_MAX LCD_STR_THERMOMETER " Max"
#define MSG_FACTOR LCD_STR_THERMOMETER " Fact"
#define MSG_AUTOTEMP "Temperatura Automatica"
#define MSG_AUTOTEMP "Temperatura Auto."
#define MSG_ON "Encender"
#define MSG_OFF "Apagar"
#define MSG_PID_P "PID-P"
#define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_E1 " E1"
#define MSG_E2 " E2"
#define MSG_E3 " E3"
#define MSG_E4 " E4"
#define MSG_ACC "Aceleracion"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax"
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "Vel. viaje min"
#define MSG_AMAX "Acel. max"
@@ -132,14 +111,10 @@
#define MSG_VOLUMETRIC "Filamento"
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
#define MSG_FILAMENT_DIAM "Fil. Dia."
#define MSG_DIAM_E1 " 1"
#define MSG_DIAM_E2 " 2"
#define MSG_DIAM_E3 " 3"
#define MSG_DIAM_E4 " 4"
#define MSG_CONTRAST "Contraste"
#define MSG_STORE_EPROM "Guardar memoria"
#define MSG_LOAD_EPROM "Cargar memoria"
#define MSG_RESTORE_FAILSAFE "Restaurar memoria."
#define MSG_RESTORE_FAILSAFE "Restaurar memoria"
#define MSG_REFRESH "Volver a cargar"
#define MSG_WATCH "Informacion"
#define MSG_PREPARE "Preparar"
@@ -154,7 +129,7 @@
#define MSG_RESUMING "Resumiendo impre."
#define MSG_PRINT_ABORTED "Impresion cancelada"
#define MSG_NO_MOVE "Sin movimiento"
#define MSG_KILLED "Parada de emergencia."
#define MSG_KILLED "Parada de emergencia"
#define MSG_STOPPED "Detenida"
#define MSG_CONTROL_RETRACT "Retraer mm"
#define MSG_CONTROL_RETRACT_SWAP "Interc. Retraer mm"
@@ -176,20 +151,63 @@
#define MSG_BABYSTEP_Z "Micropaso Z"
#define MSG_ENDSTOP_ABORT "Cancelado - Endstop"
#define MSG_HEATING_FAILED_LCD "Error: al calentar"
#define MSG_ERR_REDUNDANT_TEMP "Error: temperatura redundante"
#define MSG_ERR_REDUNDANT_TEMP "Error: temperatura"
#define MSG_THERMAL_RUNAWAY "Error de temperatura"
#define MSG_ERR_MAXTEMP "Error: Temp Maxima"
#define MSG_ERR_MINTEMP "Error: Temp Minima"
#define MSG_ERR_MAXTEMP_BED "Error: Temp Max Plataforma"
#define MSG_ERR_MINTEMP_BED "Error: Temp Min Plataforma"
#define MSG_ERR_MAXTEMP_BED "Error: Temp Max Plat"
#define MSG_ERR_MINTEMP_BED "Error: Temp Min Plat"
#define MSG_HEATING "Calentando..."
#define MSG_HEATING_COMPLETE "Calentamiento Completo"
#define MSG_BED_HEATING "Calentando plataforma ..."
#define MSG_HEATING_COMPLETE "Calentamiento listo"
#define MSG_BED_HEATING "Calentando Plat..."
#define MSG_BED_DONE "Plataforma Caliente"
#define MSG_DELTA_CALIBRATE "Calibracion Delta"
#define MSG_DELTA_CALIBRATE_X "Calibrar X"
#define MSG_DELTA_CALIBRATE_Y "Calibrar Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrar Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrar Centro"
#define MSG_INFO_MENU "Inf. Impresora"
#define MSG_INFO_PRINTER_MENU "Inf. Impresora"
#define MSG_INFO_STATS_MENU "Estadisticas Imp."
#define MSG_INFO_BOARD_MENU "Inf. Controlador"
#define MSG_INFO_THERMISTOR_MENU "Termistores"
#define MSG_INFO_EXTRUDERS "Extrusores"
#define MSG_INFO_BAUDRATE "Baudios"
#define MSG_INFO_PROTOCOL "Protocolo"
#define MSG_INFO_PRINT_COUNT "Conteo de impresion"
#define MSG_INFO_COMPLETED_PRINTS "Completadas"
#define MSG_INFO_PRINT_TIME "Tiempo total de imp."
#define MSG_INFO_PRINT_LONGEST "Impresion mas larga"
#define MSG_INFO_PRINT_FILAMENT "Total de Extrusion"
#define MSG_INFO_PRINT_COUNT "Impresiones"
#define MSG_INFO_COMPLETED_PRINTS "Completadas"
#define MSG_INFO_PRINT_TIME "Total"
#define MSG_INFO_PRINT_LONGEST "Mas larga"
#define MSG_INFO_PRINT_FILAMENT "Extrusion"
#define MSG_INFO_MIN_TEMP "Temperatura minima"
#define MSG_INFO_MAX_TEMP "Temperatura maxima"
#define MSG_INFO_PSU "Fuente de poder"
#define MSG_FILAMENT_CHANGE_HEADER "Cambiar Filamento"
#define MSG_FILAMENT_CHANGE_OPTION_HEADER "Opciones de cambio:"
#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "Extruir mas"
#define MSG_FILAMENT_CHANGE_OPTION_RESUME "Resumir imp."
#define MSG_FILAMENT_CHANGE_INIT_1 "Esperando iniciar"
#define MSG_FILAMENT_CHANGE_INIT_2 "del filamento"
#define MSG_FILAMENT_CHANGE_INIT_3 "cambiar"
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Esperado por"
#define MSG_FILAMENT_CHANGE_UNLOAD_2 "filamento expulsado"
#define MSG_FILAMENT_CHANGE_UNLOAD_3 ""
#define MSG_FILAMENT_CHANGE_INSERT_1 "Inserte filamento"
#define MSG_FILAMENT_CHANGE_INSERT_2 "y presione el boton"
#define MSG_FILAMENT_CHANGE_INSERT_3 "para continuar..."
#define MSG_FILAMENT_CHANGE_LOAD_1 "Esperado por"
#define MSG_FILAMENT_CHANGE_LOAD_2 "Cargar filamento"
#define MSG_FILAMENT_CHANGE_LOAD_3 ""
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Esperado por"
#define MSG_FILAMENT_CHANGE_EXTRUDE_2 "Extruir filamento"
#define MSG_FILAMENT_CHANGE_EXTRUDE_3 ""
#define MSG_FILAMENT_CHANGE_RESUME_1 "Esperando imp."
#define MSG_FILAMENT_CHANGE_RESUME_2 "para resumir"
#define MSG_FILAMENT_CHANGE_RESUME_3 ""
#endif // LANGUAGE_ES_H

View File

@@ -30,8 +30,6 @@
#ifndef LANGUAGE_EU_H
#define LANGUAGE_EU_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " prest."
@@ -88,14 +86,11 @@
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_ACC "Azelerazioa"
#define MSG_VXY_JERK "Vxy-astindua"
#define MSG_VX_JERK "Vx-astindua"
#define MSG_VY_JERK "Vy-astindua"
#define MSG_VZ_JERK "Vz-astindua"
#define MSG_VE_JERK "Ve-astindua"
#define MSG_VMAX "Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "

View File

@@ -31,8 +31,6 @@
#define LANGUAGE_FI_H
#define MAPPER_C2C3
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " valmis."
@@ -89,14 +87,11 @@
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_ACC "Kiihtyv"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VLiike min"
#define MSG_AMAX "Amax "

View File

@@ -30,22 +30,25 @@
#ifndef LANGUAGE_FR_H
#define LANGUAGE_FR_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " prete."
#define MSG_SD_INSERTED "Carte inseree"
#define MSG_SD_REMOVED "Carte retiree"
#define MSG_LCD_ENDSTOPS "Butées" // Max length 8 characters
#define MSG_MAIN "Menu principal"
#define MSG_AUTOSTART "Demarrage auto"
#define MSG_DISABLE_STEPPERS "Arreter moteurs"
#define MSG_AUTO_HOME "Origine auto."
#define MSG_AUTO_HOME_X "Origine X Auto."
#define MSG_AUTO_HOME_Y "Origine Y Auto."
#define MSG_AUTO_HOME_Z "Origine Z Auto."
#define MSG_LEVEL_BED_HOMING "Origine XYZ"
#define MSG_LEVEL_BED_WAITING "Cliquer pour commencer"
#define MSG_LEVEL_BED_WAITING "Clic pour commencer"
#define MSG_LEVEL_BED_NEXT_POINT "Point suivant"
#define MSG_LEVEL_BED_DONE "Mise a niveau OK!"
#define MSG_LEVEL_BED_CANCEL "Annuler"
#define MSG_SET_HOME_OFFSETS "Regler decal. origine"
#define MSG_SET_HOME_OFFSETS "Regl. decal. origine"
#define MSG_HOME_OFFSETS_APPLIED "Decalages appliques"
#define MSG_SET_ORIGIN "Regler origine"
#define MSG_PREHEAT_1 "Prechauffage PLA"
@@ -76,7 +79,7 @@
#define MSG_BED_Z "Plateau Z"
#define MSG_NOZZLE "Buse"
#define MSG_BED "Plateau"
#define MSG_FAN_SPEED "Vite. ventilateur"
#define MSG_FAN_SPEED "Vitesse ventil."
#define MSG_FLOW "Flux"
#define MSG_CONTROL "Controler"
#define MSG_MIN LCD_STR_THERMOMETER " Min"
@@ -89,15 +92,13 @@
#define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_ACC "Accel"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_SELECT "Selectionner"
#define MSG_ACC "Acceleration"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax"
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "Vdepl min"
#define MSG_AMAX "Amax "
@@ -129,7 +130,7 @@
#define MSG_USERWAIT "Atten. de l'util."
#define MSG_RESUMING "Repri. de l'impr."
#define MSG_PRINT_ABORTED "Impr. Annulee"
#define MSG_NO_MOVE "Aucun mouvement."
#define MSG_NO_MOVE "Moteurs bloques."
#define MSG_KILLED "MORT."
#define MSG_STOPPED "STOPPE."
#define MSG_CONTROL_RETRACT "Retraction mm"
@@ -144,28 +145,100 @@
#define MSG_INIT_SDCARD "Init. la carte SD"
#define MSG_CNG_SDCARD "Changer de carte"
#define MSG_ZPROBE_OUT "Z sonde exte. lit"
#define MSG_HOME "Home" // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST
#define MSG_FIRST "first"
#define MSG_BLTOUCH_SELFTEST "Autotest BLTouch"
#define MSG_BLTOUCH_RESET "RaZ BLTouch"
#define MSG_HOME "Origine" // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST
#define MSG_FIRST "Premier"
#define MSG_ZPROBE_ZOFFSET "Decalage Z"
#define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_Y "Babystep Y"
#define MSG_BABYSTEP_Z "Babystep Z"
#define MSG_ENDSTOP_ABORT "Butee abandon"
#define MSG_HEATING_FAILED_LCD "Erreur de chauffe"
#define MSG_ERR_REDUNDANT_TEMP "Err: ERREUR TEMP. REDONDANTE"
#define MSG_THERMAL_RUNAWAY "EMBALLEMENT THERMIQUE"
#define MSG_ERR_REDUNDANT_TEMP "Err: TEMP. REDONDANT"
#define MSG_THERMAL_RUNAWAY "EMBALLEMENT THERM."
#define MSG_ERR_MAXTEMP "Err: TEMP. MAX"
#define MSG_ERR_MINTEMP "Err: TEMP. MIN"
#define MSG_ERR_MAXTEMP_BED "Err: TEMP. MAX PLATEAU"
#define MSG_ERR_MINTEMP_BED "Err: TEMP. MIN PLATEAU"
#define MSG_ERR_MAXTEMP_BED "Err: TEMP. MAX LIT"
#define MSG_ERR_MINTEMP_BED "Err: TEMP. MIN LIT"
#define MSG_ERR_Z_HOMING "G28 Z interdit"
#define MSG_HALTED "IMPR. STOPPEE"
#define MSG_PLEASE_RESET "RaZ. SVP"
#define MSG_SHORT_DAY "j" // One character only
#define MSG_SHORT_HOUR "h" // One character only
#define MSG_SHORT_MINUTE "m" // One character only
#define MSG_HEATING "En chauffe..."
#define MSG_HEATING_COMPLETE "Chauffe terminee"
#define MSG_BED_HEATING "Plateau en chauffe..."
#define MSG_BED_DONE "Chauffe plateau terminee"
#define MSG_BED_HEATING "Plateau en chauffe.."
#define MSG_BED_DONE "Chauffe lit terminee"
#define MSG_DELTA_CALIBRATE "Calibration Delta"
#define MSG_DELTA_CALIBRATE_X "Calibrer X"
#define MSG_DELTA_CALIBRATE_Y "Calibrer Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrer Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrer centre"
#define MSG_INFO_MENU "Infos imprimante"
#define MSG_INFO_PRINTER_MENU "Infos imprimante"
#define MSG_INFO_STATS_MENU "Stats. imprimante"
#define MSG_INFO_BOARD_MENU "Infos carte"
#define MSG_INFO_THERMISTOR_MENU "Thermistors"
#define MSG_INFO_EXTRUDERS "Extruders"
#define MSG_INFO_BAUDRATE "Baud"
#define MSG_INFO_PROTOCOL "Protocole"
#if LCD_WIDTH >= 20
#define MSG_INFO_PRINT_COUNT "Nbre impressions"
#define MSG_INFO_COMPLETED_PRINTS "Terminees"
#define MSG_INFO_PRINT_TIME "Tps impr. total"
#define MSG_INFO_PRINT_LONGEST "Impr. la + longue"
#define MSG_INFO_PRINT_FILAMENT "Total filament"
#else
#define MSG_INFO_PRINT_COUNT "Impressions"
#define MSG_INFO_COMPLETED_PRINTS "Terminees"
#define MSG_INFO_PRINT_TIME "Total"
#define MSG_INFO_PRINT_LONGEST "+ long"
#define MSG_INFO_PRINT_FILAMENT "Filament"
#endif
#define MSG_INFO_MIN_TEMP "Temp Min"
#define MSG_INFO_MAX_TEMP "Temp Max"
#define MSG_INFO_PSU "Alimentation"
#define MSG_DRIVE_STRENGTH "Puiss. moteur "
#define MSG_DAC_PERCENT "Driver %"
#define MSG_DAC_EEPROM_WRITE "DAC EEPROM sauv."
#define MSG_FILAMENT_CHANGE_HEADER "CHANGER FILAMENT"
#define MSG_FILAMENT_CHANGE_OPTION_HEADER "CHANGER OPTIONS:"
#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "+ extrusion"
#define MSG_FILAMENT_CHANGE_OPTION_RESUME "Reprendre impr."
#if LCD_HEIGHT >= 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Attente Demarrage"
#define MSG_FILAMENT_CHANGE_INIT_2 "du filament"
#define MSG_FILAMENT_CHANGE_INIT_3 "changer"
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "attente de"
#define MSG_FILAMENT_CHANGE_UNLOAD_2 "decharger filament"
#define MSG_FILAMENT_CHANGE_UNLOAD_3 ""
#define MSG_FILAMENT_CHANGE_INSERT_1 "inserer filament"
#define MSG_FILAMENT_CHANGE_INSERT_2 "et app. bouton"
#define MSG_FILAMENT_CHANGE_INSERT_3 "pour continuer..."
#define MSG_FILAMENT_CHANGE_LOAD_1 "attente de"
#define MSG_FILAMENT_CHANGE_LOAD_2 "charger filament"
#define MSG_FILAMENT_CHANGE_LOAD_3 ""
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "attente de"
#define MSG_FILAMENT_CHANGE_EXTRUDE_2 "extrusion fil."
#define MSG_FILAMENT_CHANGE_EXTRUDE_3 ""
#define MSG_FILAMENT_CHANGE_RESUME_1 "attente impression"
#define MSG_FILAMENT_CHANGE_RESUME_2 "pour reprendre"
#define MSG_FILAMENT_CHANGE_RESUME_3 ""
#else // LCD_HEIGHT < 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Patientez..."
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Ejection..."
#define MSG_FILAMENT_CHANGE_INSERT_1 "Inserer et click"
#define MSG_FILAMENT_CHANGE_LOAD_1 "Chargement..."
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Extrusion..."
#define MSG_FILAMENT_CHANGE_RESUME_1 "Reprise..."
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_FR_H

View File

@@ -31,8 +31,6 @@
#define LANGUAGE_GL_H
#define MAPPER_C2C3
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " lista."
@@ -64,10 +62,6 @@
#define MSG_PREHEAT_2_ALL "Preque. ABS Todo"
#define MSG_PREHEAT_2_BEDONLY "Preque. ABS Cama"
#define MSG_PREHEAT_2_SETTINGS "Preque. ABS conf"
#define MSG_H1 "1"
#define MSG_H2 "2"
#define MSG_H3 "3"
#define MSG_H4 "4"
#define MSG_COOLDOWN "Arrefriar"
#define MSG_SWITCH_PS_ON "Acender"
#define MSG_SWITCH_PS_OFF "Apagar"
@@ -79,20 +73,12 @@
#define MSG_MOVE_Y "Mover Y"
#define MSG_MOVE_Z "Mover Z"
#define MSG_MOVE_E "Extrusor"
#define MSG_MOVE_E1 "1"
#define MSG_MOVE_E2 "2"
#define MSG_MOVE_E3 "3"
#define MSG_MOVE_E4 "4"
#define MSG_MOVE_01MM "Mover 0.1mm"
#define MSG_MOVE_1MM "Mover 1mm"
#define MSG_MOVE_10MM "Mover 10mm"
#define MSG_SPEED "Velocidade"
#define MSG_BED_Z "Cama Z"
#define MSG_NOZZLE "Bico"
#define MSG_N1 " 1"
#define MSG_N2 " 2"
#define MSG_N3 " 3"
#define MSG_N4 " 4"
#define MSG_BED "Cama"
#define MSG_FAN_SPEED "Velocidade vent."
#define MSG_FLOW "Fluxo"
@@ -108,19 +94,12 @@
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_SELECT "Escolla"
#define MSG_E1 " E1"
#define MSG_E2 " E2"
#define MSG_E3 " E3"
#define MSG_E4 " E4"
#define MSG_ACC "Acel"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "
@@ -135,10 +114,6 @@
#define MSG_VOLUMETRIC "Filamento"
#define MSG_VOLUMETRIC_ENABLED "E en mm3"
#define MSG_FILAMENT_DIAM "Diam. fil."
#define MSG_DIAM_E1 " 1"
#define MSG_DIAM_E2 " 2"
#define MSG_DIAM_E3 " 3"
#define MSG_DIAM_E4 " 4"
#define MSG_CONTRAST "Constraste LCD"
#define MSG_STORE_EPROM "Gardar en memo."
#define MSG_LOAD_EPROM "Cargar de memo."
@@ -172,6 +147,8 @@
#define MSG_CNG_SDCARD "Cambiar SD"
#define MSG_ZPROBE_OUT "Sonda-Z sen cama"
#define MSG_HOME "Home" // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST
#define MSG_BLTOUCH_SELFTEST "Comprobar BLTouch"
#define MSG_BLTOUCH_RESET "Iniciar BLTouch"
#define MSG_FIRST "first"
#define MSG_ZPROBE_ZOFFSET "Offset Z"
#define MSG_BABYSTEP_X "Micropaso X"
@@ -185,6 +162,7 @@
#define MSG_ERR_MINTEMP "Err: temp. min."
#define MSG_ERR_MAXTEMP_BED "Err: MAXTEMP BED"
#define MSG_ERR_MINTEMP_BED "Err: MINTEMP BED"
#define MSG_ERR_Z_HOMING "G28 Z impedido"
#define MSG_HALTED "SISTEMA MORTO"
#define MSG_PLEASE_RESET "Debe reiniciar!"
#define MSG_SHORT_DAY "d" // One character only
@@ -207,52 +185,57 @@
#define MSG_INFO_EXTRUDERS "Extrusores"
#define MSG_INFO_BAUDRATE "Baudios"
#define MSG_INFO_PROTOCOL "Protocolo"
#if LCD_WIDTH > 19
#define MSG_INFO_PRINT_COUNT "Total traballos"
#define MSG_INFO_COMPLETED_PRINTS "Total completos"
#define MSG_INFO_PRINT_TIME "Tempo impresion"
#define MSG_INFO_PRINT_LONGEST "Traballo +longo"
#define MSG_INFO_PRINT_FILAMENT "Total extruido"
#define MSG_LIGHTS_ON "Acender a luz"
#define MSG_LIGHTS_OFF "Apagar a luz"
#if LCD_WIDTH >= 20
#define MSG_INFO_PRINT_COUNT "Total traballos"
#define MSG_INFO_COMPLETED_PRINTS "Total completos"
#define MSG_INFO_PRINT_TIME "Tempo impresion"
#define MSG_INFO_PRINT_LONGEST "Traballo +longo"
#define MSG_INFO_PRINT_FILAMENT "Total extruido"
#else
#define MSG_INFO_PRINT_COUNT "Traballos"
#define MSG_INFO_COMPLETED_PRINTS "Completos"
#define MSG_INFO_PRINT_TIME "Tempo"
#define MSG_INFO_PRINT_LONGEST "O +longo"
#define MSG_INFO_PRINT_FILAMENT "Extruido"
#define MSG_INFO_PRINT_COUNT "Traballos"
#define MSG_INFO_COMPLETED_PRINTS "Completos"
#define MSG_INFO_PRINT_TIME "Tempo"
#define MSG_INFO_PRINT_LONGEST "O +longo"
#define MSG_INFO_PRINT_FILAMENT "Extruido"
#endif
#define MSG_INFO_MIN_TEMP "Min Temp"
#define MSG_INFO_MAX_TEMP "Max Temp"
#define MSG_INFO_PSU "Fonte alime."
#define MSG_DRIVE_STRENGTH "Potencia motor"
#define MSG_DAC_PERCENT "Motor %"
#define MSG_DAC_EEPROM_WRITE "Garda DAC EEPROM"
#define MSG_FILAMENT_CHANGE_HEADER "TROCO FILAMENTO"
#define MSG_FILAMENT_CHANGE_OPTION_HEADER "OPCIONS TROCO:"
#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "Extruir mais"
#define MSG_FILAMENT_CHANGE_OPTION_RESUME "Segue traballo"
#if LCD_HEIGHT >= 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Agarde para"
#define MSG_FILAMENT_CHANGE_INIT_2 "iniciar troco"
#define MSG_FILAMENT_CHANGE_INIT_3 "de filamento"
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Agarde pola"
#define MSG_FILAMENT_CHANGE_UNLOAD_2 "descarga do"
#define MSG_FILAMENT_CHANGE_UNLOAD_3 "filamento"
#define MSG_FILAMENT_CHANGE_INSERT_1 "Introduza o"
#define MSG_FILAMENT_CHANGE_INSERT_2 "filamento e"
#define MSG_FILAMENT_CHANGE_INSERT_3 "faga click"
#define MSG_FILAMENT_CHANGE_LOAD_1 "Agarde pola"
#define MSG_FILAMENT_CHANGE_LOAD_2 "carga do"
#define MSG_FILAMENT_CHANGE_LOAD_3 "filamento"
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Agarde pola"
#define MSG_FILAMENT_CHANGE_EXTRUDE_2 "extrusion do"
#define MSG_FILAMENT_CHANGE_EXTRUDE_3 "filamento"
#define MSG_FILAMENT_CHANGE_RESUME_1 "Agarde para"
#define MSG_FILAMENT_CHANGE_RESUME_2 "seguir co"
#define MSG_FILAMENT_CHANGE_RESUME_3 "traballo"
#define MSG_FILAMENT_CHANGE_INIT_1 "Agarde para"
#define MSG_FILAMENT_CHANGE_INIT_2 "iniciar troco"
#define MSG_FILAMENT_CHANGE_INIT_3 "de filamento"
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Agarde pola"
#define MSG_FILAMENT_CHANGE_UNLOAD_2 "descarga do"
#define MSG_FILAMENT_CHANGE_UNLOAD_3 "filamento"
#define MSG_FILAMENT_CHANGE_INSERT_1 "Introduza o"
#define MSG_FILAMENT_CHANGE_INSERT_2 "filamento e"
#define MSG_FILAMENT_CHANGE_INSERT_3 "faga click"
#define MSG_FILAMENT_CHANGE_LOAD_1 "Agarde pola"
#define MSG_FILAMENT_CHANGE_LOAD_2 "carga do"
#define MSG_FILAMENT_CHANGE_LOAD_3 "filamento"
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Agarde pola"
#define MSG_FILAMENT_CHANGE_EXTRUDE_2 "extrusion do"
#define MSG_FILAMENT_CHANGE_EXTRUDE_3 "filamento"
#define MSG_FILAMENT_CHANGE_RESUME_1 "Agarde para"
#define MSG_FILAMENT_CHANGE_RESUME_2 "seguir co"
#define MSG_FILAMENT_CHANGE_RESUME_3 "traballo"
#else // LCD_HEIGHT < 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Agarde..."
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Descargando..."
#define MSG_FILAMENT_CHANGE_INSERT_1 "Introduza e click"
#define MSG_FILAMENT_CHANGE_LOAD_1 "Cargando..."
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Extruindo..."
#define MSG_FILAMENT_CHANGE_RESUME_1 "Seguindo..."
#define MSG_FILAMENT_CHANGE_INIT_1 "Agarde..."
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Descargando..."
#define MSG_FILAMENT_CHANGE_INSERT_1 "Introduza e click"
#define MSG_FILAMENT_CHANGE_LOAD_1 "Cargando..."
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Extruindo..."
#define MSG_FILAMENT_CHANGE_RESUME_1 "Seguindo..."
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_GL_H

View File

@@ -30,9 +30,6 @@
#ifndef LANGUAGE_HR_H
#define LANGUAGE_HR_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1 // use the better font on full graphic displays.
#define WELCOME_MSG MACHINE_NAME " spreman."
@@ -47,7 +44,7 @@
#define MSG_AUTO_HOME_Y "Home-aj Y"
#define MSG_AUTO_HOME_Z "Home-aj Z"
#define MSG_LEVEL_BED_HOMING "Home-aj XYZ"
#define MSG_LEVEL_BED_WAITING "Click to Begin"
#define MSG_LEVEL_BED_WAITING "Klikni za početak"
#define MSG_LEVEL_BED_NEXT_POINT "Sljedeća točka"
#define MSG_LEVEL_BED_DONE "Niveliranje gotovo!"
#define MSG_LEVEL_BED_CANCEL "Otkaži"
@@ -64,10 +61,6 @@
#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 " Sve"
#define MSG_PREHEAT_2_BEDONLY MSG_PREHEAT_2 " Bed"
#define MSG_PREHEAT_2_SETTINGS MSG_PREHEAT_2 " conf"
#define MSG_H1 "1"
#define MSG_H2 "2"
#define MSG_H3 "3"
#define MSG_H4 "4"
#define MSG_COOLDOWN "Hlađenje"
#define MSG_SWITCH_PS_ON "Uključi napajanje"
#define MSG_SWITCH_PS_OFF "Isključi napajanje"
@@ -79,20 +72,12 @@
#define MSG_MOVE_Y "Miči Y"
#define MSG_MOVE_Z "Miči Z"
#define MSG_MOVE_E "Extruder"
#define MSG_MOVE_E1 "1"
#define MSG_MOVE_E2 "2"
#define MSG_MOVE_E3 "3"
#define MSG_MOVE_E4 "4"
#define MSG_MOVE_01MM "Miči 0.1mm"
#define MSG_MOVE_1MM "Miči 1mm"
#define MSG_MOVE_10MM "Miči 10mm"
#define MSG_SPEED "Brzina"
#define MSG_BED_Z "Bed Z"
#define MSG_NOZZLE "Nozzle"
#define MSG_N1 " 1"
#define MSG_N2 " 2"
#define MSG_N3 " 3"
#define MSG_N4 " 4"
#define MSG_NOZZLE "Dizna"
#define MSG_BED "Bed"
#define MSG_FAN_SPEED "Brzina ventilatora"
#define MSG_FLOW "Flow"
@@ -107,19 +92,12 @@
#define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_E1 " E1"
#define MSG_E2 " E2"
#define MSG_E3 " E3"
#define MSG_E4 " E4"
#define MSG_ACC "Accel"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "
@@ -130,14 +108,10 @@
#define MSG_ZSTEPS "Zsteps/mm"
#define MSG_ESTEPS "Esteps/mm"
#define MSG_TEMPERATURE "Temperature"
#define MSG_MOTION "Motion"
#define MSG_MOTION "Gibanje"
#define MSG_VOLUMETRIC "Filament"
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
#define MSG_FILAMENT_DIAM "Fil. Dia."
#define MSG_DIAM_E1 " 1"
#define MSG_DIAM_E2 " 2"
#define MSG_DIAM_E3 " 3"
#define MSG_DIAM_E4 " 4"
#define MSG_CONTRAST "Kontrast LCD-a"
#define MSG_STORE_EPROM "Pohrani u memoriju"
#define MSG_LOAD_EPROM "Učitaj memoriju"
@@ -170,6 +144,8 @@
#define MSG_INIT_SDCARD "Init. SD karticu"
#define MSG_CNG_SDCARD "Promijeni SD karticu"
#define MSG_ZPROBE_OUT "Z probe out. bed"
#define MSG_BLTOUCH_SELFTEST "BLTouch Self-Test"
#define MSG_BLTOUCH_RESET "Reset BLTouch"
#define MSG_HOME "Home" // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST
#define MSG_FIRST "first"
#define MSG_ZPROBE_ZOFFSET "Z Offset"
@@ -177,13 +153,19 @@
#define MSG_BABYSTEP_Y "Babystep Y"
#define MSG_BABYSTEP_Z "Babystep Z"
#define MSG_ENDSTOP_ABORT "Endstop abort"
#define MSG_HEATING_FAILED_LCD "Heating failed"
#define MSG_HEATING_FAILED_LCD "Grijanje neuspješno"
#define MSG_ERR_REDUNDANT_TEMP "Err: REDUNDANT TEMP"
#define MSG_THERMAL_RUNAWAY "THERMAL RUNAWAY"
#define MSG_ERR_MAXTEMP "Err: MAXTEMP"
#define MSG_ERR_MINTEMP "Err: MINTEMP"
#define MSG_ERR_MAXTEMP_BED "Err: MAXTEMP BED"
#define MSG_ERR_MINTEMP_BED "Err: MINTEMP BED"
#define MSG_ERR_Z_HOMING "G28 Z Forbidden"
#define MSG_HALTED "PRINTER HALTED"
#define MSG_PLEASE_RESET "Please reset"
#define MSG_SHORT_DAY "d" // One character only
#define MSG_SHORT_HOUR "h" // One character only
#define MSG_SHORT_MINUTE "m" // One character only
#define MSG_HEATING "Grijanje..."
#define MSG_HEATING_COMPLETE "Grijanje gotovo."
#define MSG_BED_HEATING "Grijanje Bed-a."
@@ -193,5 +175,61 @@
#define MSG_DELTA_CALIBRATE_Y "Kalibriraj Y"
#define MSG_DELTA_CALIBRATE_Z "Kalibriraj Z"
#define MSG_DELTA_CALIBRATE_CENTER "Kalibriraj Središte"
#define MSG_INFO_MENU "O printeru"
#define MSG_INFO_PRINTER_MENU "Podaci o printeru"
#define MSG_INFO_STATS_MENU "Statistika printera"
#define MSG_INFO_BOARD_MENU "Podaci o elektronici"
#define MSG_INFO_THERMISTOR_MENU "Termistori"
#define MSG_INFO_EXTRUDERS "Extruderi"
#define MSG_INFO_BAUDRATE "Baud"
#define MSG_INFO_PROTOCOL "Protokol"
#define MSG_LIGHTS_ON "Upali osvjetljenje"
#define MSG_LIGHTS_OFF "Ugasi osvjetljenje"
#if LCD_WIDTH >= 20
#define MSG_INFO_PRINT_COUNT "Broj printova"
#define MSG_INFO_COMPLETED_PRINTS "Završeni"
#define MSG_INFO_PRINT_TIME "Ukupno vrijeme printanja"
#define MSG_INFO_PRINT_LONGEST "Trajanje najdužeg printa"
#define MSG_INFO_PRINT_FILAMENT "Extrudirano ukupno"
#else
#define MSG_INFO_PRINT_COUNT "Printovi"
#define MSG_INFO_COMPLETED_PRINTS "Završeni"
#define MSG_INFO_PRINT_TIME "Ukupno"
#define MSG_INFO_PRINT_LONGEST "Najduži"
#define MSG_INFO_PRINT_FILAMENT "Extrudirano"
#endif
#define MSG_INFO_MIN_TEMP "Min Temp"
#define MSG_INFO_MAX_TEMP "Max Temp"
#define MSG_INFO_PSU "Napajanje"
#define MSG_DRIVE_STRENGTH "Drive Strength"
#define MSG_DAC_PERCENT "Driver %"
#define MSG_DAC_EEPROM_WRITE "DAC EEPROM Write"
#define MSG_FILAMENT_CHANGE_HEADER "CHANGE FILAMENT"
#define MSG_FILAMENT_CHANGE_OPTION_HEADER "CHANGE OPTIONS:"
#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "Extrudiraj više"
#define MSG_FILAMENT_CHANGE_OPTION_RESUME "Nastavi print"
#if LCD_HEIGHT >= 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Čekaj početak"
#define MSG_FILAMENT_CHANGE_INIT_2 "filamenta"
#define MSG_FILAMENT_CHANGE_INIT_3 "promijeni"
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Čekaj"
#define MSG_FILAMENT_CHANGE_UNLOAD_2 "filament unload"
#define MSG_FILAMENT_CHANGE_INSERT_1 "Umetni filament"
#define MSG_FILAMENT_CHANGE_INSERT_2 "i pritisni tipku"
#define MSG_FILAMENT_CHANGE_INSERT_3 "za nastavak..."
#define MSG_FILAMENT_CHANGE_LOAD_1 "Pričekaj"
#define MSG_FILAMENT_CHANGE_LOAD_2 "filament load"
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Pričekaj"
#define MSG_FILAMENT_CHANGE_EXTRUDE_2 "filament extrude"
#define MSG_FILAMENT_CHANGE_RESUME_1 "Wait for print"
#define MSG_FILAMENT_CHANGE_RESUME_2 "to resume"
#else // LCD_HEIGHT < 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Pričekaj..."
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Ejecting..."
#define MSG_FILAMENT_CHANGE_INSERT_1 "Insert and Click"
#define MSG_FILAMENT_CHANGE_LOAD_1 "Loading..."
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Extrudiranje..."
#define MSG_FILAMENT_CHANGE_RESUME_1 "Nastavljam..."
#endif
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_HR_H

View File

@@ -30,8 +30,6 @@
#ifndef LANGUAGE_IT_H
#define LANGUAGE_IT_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " pronto."
@@ -46,7 +44,7 @@
#define MSG_AUTO_HOME_Y "Home asse Y"
#define MSG_AUTO_HOME_Z "Home asse Z"
#define MSG_LEVEL_BED_HOMING "Home assi XYZ"
#define MSG_LEVEL_BED_WAITING "Premi per Iniziare"
#define MSG_LEVEL_BED_WAITING "Premi per iniziare"
#define MSG_LEVEL_BED_NEXT_POINT "Punto successivo"
#define MSG_LEVEL_BED_DONE "Livel. terminato!"
#define MSG_LEVEL_BED_CANCEL "Annulla"
@@ -77,11 +75,19 @@
#define MSG_MOVE_01MM "Muovi di 0.1mm"
#define MSG_MOVE_1MM "Muovi di 1mm"
#define MSG_MOVE_10MM "Muovi di 10mm"
#define MSG_SPEED "Velocità"
#if ENABLED(DOGLCD)
#define MSG_SPEED "Velocità"
#else
#define MSG_SPEED "Velocita"
#endif
#define MSG_BED_Z "piatto Z"
#define MSG_NOZZLE "Ugello"
#define MSG_BED "Piatto"
#define MSG_FAN_SPEED "Velocità ventola"
#if ENABLED(DOGLCD)
#define MSG_FAN_SPEED "Velocità ventola"
#else
#define MSG_FAN_SPEED "Velocita ventola"
#endif
#define MSG_FLOW "Flusso"
#define MSG_CONTROL "Controllo"
#define MSG_MIN LCD_STR_THERMOMETER " Min"
@@ -96,14 +102,11 @@
#define MSG_PID_C "PID-C"
#define MSG_SELECT "Seleziona"
#define MSG_ACC "Accel"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "
@@ -150,8 +153,10 @@
#define MSG_INIT_SDCARD "Iniz. SD-Card"
#define MSG_CNG_SDCARD "Cambia SD-Card"
#define MSG_ZPROBE_OUT "Z probe out. bed"
#define MSG_BLTOUCH_SELFTEST "Autotest BLTouch"
#define MSG_BLTOUCH_RESET "Resetta BLTouch"
#define MSG_HOME "Home" // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST
#define MSG_FIRST "first"
#define MSG_FIRST "prima"
#define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_Y "Babystep Y"
@@ -164,6 +169,7 @@
#define MSG_ERR_MINTEMP "Err: TEMP MINIMA"
#define MSG_ERR_MAXTEMP_BED "Err: TEMP MASSIMA PIATTO"
#define MSG_ERR_MINTEMP_BED "Err: TEMP MINIMA PIATTO"
#define MSG_ERR_Z_HOMING "G28 Z Vietato"
#define MSG_HALTED "STAMPANTE FERMATA"
#define MSG_PLEASE_RESET "Riavviare prego"
#define MSG_SHORT_DAY "g" // One character only
@@ -186,23 +192,36 @@
#define MSG_INFO_EXTRUDERS "Estrusori"
#define MSG_INFO_BAUDRATE "Baud"
#define MSG_INFO_PROTOCOL "Protocollo"
#if LCD_WIDTH > 19
#define MSG_LIGHTS_ON "Luci Case on"
#define MSG_LIGHTS_OFF "Luci Case off"
#if LCD_WIDTH >= 20
#define MSG_INFO_PRINT_COUNT "Contat. stampa"
#define MSG_INFO_COMPLETED_PRINTS "Completati"
#define MSG_INFO_PRINT_TIME "Tempo totale"
#define MSG_INFO_PRINT_LONGEST "Lavoro piu lungo"
#if ENABLED(DOGLCD)
#define MSG_INFO_PRINT_LONGEST "Lavoro più lungo"
#else
#define MSG_INFO_PRINT_LONGEST "Lavoro piu lungo"
#endif
#define MSG_INFO_PRINT_FILAMENT "Totale estruso"
#else
#define MSG_INFO_PRINT_COUNT "Stampe"
#define MSG_INFO_COMPLETED_PRINTS "Completati"
#define MSG_INFO_PRINT_TIME "Durata"
#define MSG_INFO_PRINT_LONGEST "Piu lungo"
#if ENABLED(DOGLCD)
#define MSG_INFO_PRINT_LONGEST "Più lungo"
#else
#define MSG_INFO_PRINT_LONGEST "Piu lungo"
#endif
#define MSG_INFO_PRINT_FILAMENT "Estruso"
#endif
#define MSG_INFO_MIN_TEMP "Temp min"
#define MSG_INFO_MAX_TEMP "Temp max"
#define MSG_INFO_PSU "Alimentatore"
#define MSG_DRIVE_STRENGTH "Potenza Drive"
#define MSG_DAC_PERCENT "Driver %"
#define MSG_DAC_EEPROM_WRITE "Scrivi DAC EEPROM"
#define MSG_FILAMENT_CHANGE_HEADER "CAMBIA FILAMENTO"
#define MSG_FILAMENT_CHANGE_OPTION_HEADER "CAMBIA OPZIONI:"
#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "Estrusione"

View File

@@ -89,7 +89,7 @@
#define MSG_MIN LCD_STR_THERMOMETER " \xbb\xb2\xc3\xb2" // " サイテイ" (" Min")
#define MSG_MAX LCD_STR_THERMOMETER " \xbb\xb2\xba\xb3" // " サイコウ" (" Max")
#define MSG_FACTOR LCD_STR_THERMOMETER " \xcc\xa7\xb8\xc0\xb0" // " ファクター" (" Fact")
#if LCD_WIDTH > 19
#if LCD_WIDTH >= 20
#define MSG_AUTOTEMP "\xbc\xde\xc4\xde\xb3\xb5\xdd\xc4\xde\xbe\xb2\xb7\xde\xae" // "ジドウオンドセイギョ" ("Autotemp")
#else
#define MSG_AUTOTEMP "\xbc\xde\xc4\xde\xb3\xb5\xdd\xc4\xde" // "ジドウオンド" ("Autotemp")
@@ -101,43 +101,45 @@
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_SELECT "\xbe\xdd\xc0\xb8" // "センタク" ("Select")
#if LCD_WIDTH > 19
#if LCD_WIDTH >= 20
#define MSG_ACC "\xb6\xbf\xb8\xc4\xde mm/s2" // "カソクド mm/s2" ("Accel")
#define MSG_VXY_JERK "XY\xbc\xde\xb8\x20\xd4\xb8\xc4\xde mm/s" // "XYジク ヤクド mm/s" ("Vxy-jerk")
#define MSG_VX_JERK "X\xbc\xde\xb8\x20\xd4\xb8\xc4\xde mm/s" // "Xジク ヤクド mm/s" ("Vx-jerk")
#define MSG_VY_JERK "Y\xbc\xde\xb8\x20\xd4\xb8\xc4\xde mm/s" // "Yジク ヤクド mm/s" ("Vy-jerk")
#define MSG_VZ_JERK "Z\xbc\xde\xb8\x20\xd4\xb8\xc4\xde mm/s" // "Zジク ヤクド mm/s" ("Vz-jerk")
#define MSG_VE_JERK "\xb4\xb8\xbd\xc4\xd9\xb0\xc0\xde\xb0\x20\xd4\xb8\xc4\xde" // "エクストルーダー ヤクド" ("Ve-jerk")
#define MSG_VMAX "\xbb\xb2\xc0\xde\xb2\xb5\xb8\xd8\xbf\xb8\xc4\xde " // "サイダイオクリソクド " ("Vmax ")
#else
#define MSG_ACC "\xb6\xbf\xb8\xc4\xde" // "カソクド" ("Accel")
#define MSG_VXY_JERK "XY\xbc\xde\xb8\x20\xd4\xb8\xc4\xde" // "XYジク ヤクド" ("Vxy-jerk")
#define MSG_VZ_JERK "Z\xbc\xde\xb8\x20\xd4\xb8\xc4\xde" // "Zジク ヤクド" ("Vz-jerk")
#define MSG_VE_JERK "E\x20\xd4\xb8\xc4\xde" // "E ヤクド" ("Ve-jerk")
#define MSG_VMAX "max\xb5\xb8\xd8\xbf\xb8\xc4\xde " // "maxオクリソクド" ("Vmax ")
#endif
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#if LCD_WIDTH > 19
#define MSG_VMIN "\xbb\xb2\xbc\xae\xb3\xb5\xb8\xd8\xbf\xb8\xc4\xde" // "サイショウオクリソクド" ("Vmin")
#define MSG_VTRAV_MIN "\xbb\xb2\xbc\xae\xb3\xb2\xc4\xde\xb3\xbf\xb8\xc4\xde" // "サイショウイドウソクド" ("VTrav min")
#define MSG_AMAX "\xbb\xb2\xc0\xde\xb2\xb6\xbf\xb8\xc4\xde " // "サイダイカソクド " ("Amax ")
#else
#define MSG_ACC "\xb6\xbf\xb8\xc4\xde" // "カソクド" ("Accel")
#define MSG_VX_JERK "X\xbc\xde\xb8\x20\xd4\xb8\xc4\xde" // "XYジク ヤクド" ("Vx-jerk")
#define MSG_VY_JERK "Y\xbc\xde\xb8\x20\xd4\xb8\xc4\xde" // "XYジク ヤクド" ("Vy-jerk")
#define MSG_VZ_JERK "Z\xbc\xde\xb8\x20\xd4\xb8\xc4\xde" // "Zジク ヤクド" ("Vz-jerk")
#define MSG_VE_JERK "E\x20\xd4\xb8\xc4\xde" // "E ヤクド" ("Ve-jerk")
#define MSG_VMAX "max\xb5\xb8\xd8\xbf\xb8\xc4\xde " // "maxオクリソクド" ("Vmax ")
#define MSG_VMIN "min\xb5\xb8\xd8\xbf\xb8\xc4\xde" // "minオクリソクド" ("Vmin")
#define MSG_VTRAV_MIN "min\xb2\xc4\xde\xb3\xbf\xb8\xc4\xde" // "minイドウソクド" ("VTrav min")
#define MSG_AMAX "max\xb6\xbf\xb8 " // "maxカソク " ("Amax ")
#endif
#define MSG_A_RETRACT "\xcb\xb7\xba\xd0\xb6\xbf\xb8\xc4\xde" // "ヒキコミカソクド" ("A-retract")
#define MSG_A_TRAVEL "\xb2\xc4\xde\xb3\xb6\xbf\xb8\xc4\xde" // "イドウカソクド" ("A-travel")
#define MSG_XSTEPS "Xsteps/mm"
#define MSG_YSTEPS "Ysteps/mm"
#define MSG_ZSTEPS "Zsteps/mm"
#define MSG_ESTEPS "Esteps/mm"
#if LCD_WIDTH >= 20
#define MSG_XSTEPS "Xsteps/mm"
#define MSG_YSTEPS "Ysteps/mm"
#define MSG_ZSTEPS "Zsteps/mm"
#define MSG_ESTEPS "Esteps/mm"
#else
#define MSG_XSTEPS "Xsteps"
#define MSG_YSTEPS "Ysteps"
#define MSG_ZSTEPS "Zsteps"
#define MSG_ESTEPS "Esteps"
#endif
#define MSG_TEMPERATURE "\xb5\xdd\xc4\xde" // "オンド" ("Temperature")
#define MSG_MOTION "\xb3\xba\xde\xb7\xbe\xaf\xc3\xb2" // "ウゴキセッテイ" ("Motion")
#define MSG_VOLUMETRIC "\xcc\xa8\xd7\xd2\xdd\xc4" // "フィラメント" ("Filament")
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
#if LCD_WIDTH > 19
#if LCD_WIDTH >= 20
#define MSG_FILAMENT_DIAM "\xcc\xa8\xd7\xd2\xdd\xc4\xc1\xae\xaf\xb9\xb2" // "フィラメントチョッケイ" ("Fil. Dia.")
#else
#define MSG_FILAMENT_DIAM "\xcc\xa8\xd7\xd2\xdd\xc4\xb9\xb2" // "フィラメントケイ" ("Fil. Dia.")
@@ -162,7 +164,7 @@
#define MSG_NO_MOVE "\xb3\xba\xde\xb7\xcf\xbe\xdd" // "ウゴキマセン" ("No move.")
#define MSG_KILLED "\xcb\xbc\xde\xae\xb3\xc3\xb2\xbc" // "ヒジョウテイシ" ("KILLED. ")
#define MSG_STOPPED "\xc3\xb2\xbc\xbc\xcf\xbc\xc0" // "テイシシマシタ" ("STOPPED. ")
#if LCD_WIDTH > 19
#if LCD_WIDTH >= 20
#define MSG_CONTROL_RETRACT "\xcb\xb7\xba\xd0\xd8\xae\xb3 mm" // "ヒキコミリョウ mm" ("Retract mm")
#define MSG_CONTROL_RETRACT_SWAP "\xcb\xb7\xba\xd0\xd8\xae\xb3S mm" // "ヒキコミリョウS mm" ("Swap Re.mm")
#define MSG_CONTROL_RETRACTF "\xcb\xb7\xba\xd0\xbf\xb8\xc4\xde mm/s" // "ヒキコミソクド mm/s" ("Retract V")
@@ -184,8 +186,14 @@
#define MSG_INIT_SDCARD "SD\xb6\xb0\xc4\xde\xbb\xb2\xd6\xd0\xba\xd0" // "SDカードサイヨミコミ" ("Init. SD card")
#define MSG_CNG_SDCARD "SD\xb6\xb0\xc4\xde\xba\xb3\xb6\xdd" // "SDカードコウカン" ("Change SD card")
#define MSG_ZPROBE_OUT "Z\xcc\xdf\xdb\xb0\xcc\xde\x20\xcd\xde\xaf\xc4\xde\xb6\xde\xb2" // "Zプローブ ベッドガイ" ("Z probe out. bed")
#if LCD_WIDTH >= 20
#define MSG_BLTOUCH_SELFTEST "BLTouch \xbc\xde\xba\xbc\xdd\xc0\xde\xdd" // "BLTouch ジコシンダン" ("BLTouch Self-Test")
#else
#define MSG_BLTOUCH_SELFTEST "BLTouch \xbe\xd9\xcc\xc3\xbd\xc4" // "BLTouch セルフテスト" ("BLTouch Self-Test")
#endif
#define MSG_BLTOUCH_RESET "BLTouch \xd8\xbe\xaf\xc4" // "BLTouch リセット" ("Reset BLTouch")
#define MSG_HOME "\xbb\xb7\xc6" // "サキニ" ("Home") // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST
#if LCD_WIDTH > 19
#if LCD_WIDTH >= 20
#define MSG_FIRST "\xa6\xcc\xaf\xb7\xbb\xbe\xc3\xb8\xc0\xde\xbb\xb2" // "ヲフッキサセテクダサイ" ("first")
#else
#define MSG_FIRST "\xa6\xcc\xaf\xb7\xbb\xbe\xd6" // "ヲフッキサセヨ" ("first")
@@ -194,13 +202,13 @@
#define MSG_BABYSTEP_X "X\xbc\xde\xb8\x20\xcb\xde\xc4\xde\xb3" // "Xジク ビドウ" ("Babystep X")
#define MSG_BABYSTEP_Y "Y\xbc\xde\xb8\x20\xcb\xde\xc4\xde\xb3" // "Yジク ビドウ" ("Babystep Y")
#define MSG_BABYSTEP_Z "Z\xbc\xde\xb8\x20\xcb\xde\xc4\xde\xb3" // "Zジク ビドウ" ("Babystep Z")
#if LCD_WIDTH > 19
#if LCD_WIDTH >= 20
#define MSG_ENDSTOP_ABORT "\xb2\xc4\xde\xb3\xb9\xde\xdd\xb6\xb2\xb9\xdd\xc1\xb7\xc9\xb3" // "イドウゲンカイケンチキノウ" ("Endstop abort")
#else
#define MSG_ENDSTOP_ABORT "\xb2\xc4\xde\xb3\xb9\xde\xdd\xb6\xb2\xb9\xdd\xc1" // "イドウゲンカイケンチ" ("Endstop abort")
#endif
#define MSG_HEATING_FAILED_LCD "\xb6\xc8\xc2\xbc\xaf\xca\xdf\xb2" // "カネツシッパイ" ("Heating failed")
#if LCD_WIDTH > 19
#if LCD_WIDTH >= 20
#define MSG_ERR_REDUNDANT_TEMP "\xb4\xd7\xb0:\xbc\xde\xae\xb3\xc1\xae\xb3\xbb\xb0\xd0\xbd\xc0\xb0\xb7\xc9\xb3" // "エラー:ジョウチョウサーミスターキノウ" ("Err: REDUNDANT TEMP")
#else
#define MSG_ERR_REDUNDANT_TEMP "\xb4\xd7\xb0:\xbc\xde\xae\xb3\xc1\xae\xb3\xbb\xb0\xd0\xbd\xc0" // "エラー:ジョウチョウサーミスタ" ("Err: REDUNDANT TEMP")
@@ -208,13 +216,14 @@
#define MSG_THERMAL_RUNAWAY "\xc8\xc2\xce\xde\xb3\xbf\xb3" // "ネツボウソウ" ("THERMAL RUNAWAY")
#define MSG_ERR_MAXTEMP "\xb4\xd7\xb0:\xbb\xb2\xba\xb3\xb5\xdd\xc1\xae\xb3\xb6" // "エラー:サイコウオンチョウカ" ("Err: MAXTEMP")
#define MSG_ERR_MINTEMP "\xb4\xd7\xb0:\xbb\xb2\xc3\xb2\xb5\xdd\xd0\xcf\xdd" // "エラー:サイテイオンミマン" ("Err: MINTEMP")
#if LCD_WIDTH > 19
#if LCD_WIDTH >= 20
#define MSG_ERR_MAXTEMP_BED "\xb4\xd7\xb0:\xcd\xde\xaf\xc4\xde\x20\xbb\xb2\xba\xb3\xb5\xdd\xc1\xae\xb3\xb6" // "エラー:ベッド サイコウオンチョウカ" ("Err: MAXTEMP BED")
#define MSG_ERR_MINTEMP_BED "\xb4\xd7\xb0:\xcd\xde\xaf\xc4\xde\x20\xbb\xb2\xc3\xb2\xb5\xdd\xd0\xcf\xdd" // "エラー:ベッド サイテイオンミマン" ("Err: MINTEMP BED")
#else
#define MSG_ERR_MAXTEMP_BED "\xb4\xd7\xb0:\xcd\xde\xaf\xc4\xde\x20\xbb\xb2\xba\xb3\xb5\xdd" // "エラー:ベッド サイコウオン" ("Err: MAXTEMP BED")
#define MSG_ERR_MINTEMP_BED "\xb4\xd7\xb0:\xcd\xde\xaf\xc4\xde\x20\xbb\xb2\xc3\xb2\xb5\xdd" // "エラー:ベッド サイテイオン" ("Err: MINTEMP BED")
#endif
#define MSG_ERR_Z_HOMING MSG_HOME " " MSG_X MSG_Y " " MSG_FIRST // "サキニ XY ヲフッキサセテクダサイ" or "サキニ XY ヲフッキサセヨ" ("G28 Z Forbidden")
#define MSG_HALTED "\xcc\xdf\xd8\xdd\xc0\xb0\xca\xc3\xb2\xbc\xbc\xcf\xbc\xc0" // "プリンターハテイシシマシタ" ("PRINTER HALTED")
#define MSG_PLEASE_RESET "\xd8\xbe\xaf\xc4\xbc\xc3\xb8\xc0\xde\xbb\xb2" // "リセットシテクダサイ" ("Please reset")
#define MSG_SHORT_DAY "d" // One character only
@@ -237,22 +246,31 @@
#define MSG_INFO_EXTRUDERS "\xb4\xb8\xbd\xc4\xd9\xb0\xc0\xde\xb0\xbd\xb3" // "エクストルーダースウ" ("Extruders")
#define MSG_INFO_BAUDRATE "\xce\xde\xb0\xda\xb0\xc4" // "ボーレート" ("Baud")
#define MSG_INFO_PROTOCOL "\xcc\xdf\xdb\xc4\xba\xd9" // "プロトコル" ("Protocol")
#define MSG_INFO_PRINT_COUNT "\xcc\xdf\xd8\xdd\xc4\xbd\xb3 " // "プリントスウ " ("Print Count")
#define MSG_LIGHTS_ON "\xb7\xae\xb3\xc0\xb2\xc5\xb2\xbc\xae\xb3\xd2\xb2\x20\xb5\xdd" // "キョウタイナイショウメイ オン" ("Case light on")
#define MSG_LIGHTS_OFF "\xb7\xae\xb3\xc0\xb2\xc5\xb2\xbc\xae\xb3\xd2\xb2\x20\xb5\xcc" // "キョウタイナイショウメイ オフ" ("Case light off")
#define MSG_INFO_PRINT_COUNT "\xcc\xdf\xd8\xdd\xc4\xbd\xb3" // "プリントスウ" ("Print Count")
#define MSG_INFO_COMPLETED_PRINTS "\xb6\xdd\xd8\xae\xb3\xbd\xb3" // "カンリョウスウ" ("Completed")
#define MSG_INFO_PRINT_TIME "\xcc\xdf\xd8\xdd\xc4\xbc\xde\xb6\xdd\xd9\xb2\xb9\xb2" // "プリントジカンルイケイ" ("Total print time")
#define MSG_INFO_PRINT_LONGEST "\xbb\xb2\xc1\xae\xb3\xcc\xdf\xd8\xdd\xc4\xbc\xde\xb6\xdd" // "サイチョウプリントジカン" ("Longest job time")
#if LCD_WIDTH > 19
#if LCD_WIDTH >= 20
#define MSG_INFO_PRINT_FILAMENT "\xcc\xa8\xd7\xd2\xdd\xc4\xbc\xd6\xb3\xd8\xae\xb3\xd9\xb2\xb9\xb2" // "フィラメントシヨウリョウルイケイ" ("Extruded total")
#else
#define MSG_INFO_PRINT_FILAMENT "\xcc\xa8\xd7\xd2\xdd\xc4\xbf\xb3\xbc\xd6\xb3\xd8\xae\xb3" // "フィラメントソウシヨウリョウ" ("Extruded")
#endif
#define MSG_INFO_MIN_TEMP "\xbe\xaf\xc3\xb2\xbb\xb2\xc3\xb2\xb5\xdd" // "セッテイサイテイオン" ("Min Temp")
#define MSG_INFO_MAX_TEMP "\xbe\xaf\xc3\xb2\xbb\xb2\xba\xb3\xb5\xdd" // "セッテイサイコウオン" ("Max Temp")
#if LCD_WIDTH > 19
#if LCD_WIDTH >= 20
#define MSG_INFO_PSU "\xc3\xde\xdd\xb9\xde\xdd\xbc\xad\xcd\xde\xc2" // "デンゲンシュベツ" ("Power Supply")
#else
#define MSG_INFO_PSU "\xc3\xde\xdd\xb9\xde\xdd" // "デンゲン" ("Power Supply")
#endif
#define MSG_DRIVE_STRENGTH "\xd3\xb0\xc0\xb0\xb8\xc4\xde\xb3\xd8\xae\xb8" // "モータークドウリョク" ("Drive Strength")
#if LCD_WIDTH >= 20
#define MSG_DAC_PERCENT "DAC\xbc\xad\xc2\xd8\xae\xb8 %" // "DACシュツリョク %" ("Driver %")
#else
#define MSG_DAC_PERCENT "DAC\xbc\xad\xc2\xd8\xae\xb8" // "DACシュツリョク" ("Driver %")
#endif
#define MSG_DAC_EEPROM_WRITE MSG_STORE_EPROM // "メモリヘカクノウ" ("DAC EEPROM Write")
#define MSG_FILAMENT_CHANGE_HEADER "\xcc\xa8\xd7\xd2\xdd\xc4\xba\xb3\xb6\xdd" // "フィラメントコウカン" ("CHANGE FILAMENT")
#define MSG_FILAMENT_CHANGE_OPTION_HEADER "\xc4\xde\xb3\xbb\xa6\xbe\xdd\xc0\xb8\xbc\xc3\xb8\xc0\xde\xbb\xb2" // "ドウサヲセンタクシテクダサイ" ("CHANGE OPTIONS:")
#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "\xbb\xd7\xc6\xb5\xbc\xc0\xde\xbd" // "サラニオシダス" ("Extrude more")
@@ -279,7 +297,7 @@
#else // LCD_HEIGHT < 4
#define MSG_FILAMENT_CHANGE_INIT_1 "\xba\xb3\xb6\xdd\xa6\xb6\xb2\xbc\xbc\xcf\xbd" // "コウカンヲカイシシマス" ("Please wait...")
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "\xcc\xa8\xd7\xd2\xdd\xc4\xc7\xb7\xc0\xde\xbc\xc1\xad\xb3" // "フィラメントヌキダシチュウ" ("Ejecting...")
#if LCD_WIDTH > 19
#if LCD_WIDTH >= 20
#define MSG_FILAMENT_CHANGE_INSERT_1 "\xbf\xb3\xc6\xad\xb3\xbc\x2c\xb8\xd8\xaf\xb8\xbc\xc3\xb8\xc0\xde\xbb\xb2" // "ソウニュウシ,クリックシテクダサイ" ("Insert and Click")
#else
#define MSG_FILAMENT_CHANGE_INSERT_1 "\xbf\xb3\xc6\xad\xb3\xbc\x2c\xb8\xd8\xaf\xb8\xbe\xd6" // "ソウニュウシ,クリックセヨ" ("Insert and Click")

View File

@@ -32,8 +32,6 @@
#define LANGUAGE_KANA_UTF_H
#define MAPPER_E382E383
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_KANA
// This just to show the potential benefit of unicode.
@@ -102,14 +100,11 @@
#define MSG_PID_C "PID-C"
#define MSG_SELECT "センタク" // "Select"
#define MSG_ACC "カソクド mm/s2" // "Accel"
#define MSG_VXY_JERK "XYジク ヤクド mm/s" // "Vxy-jerk"
#define MSG_VX_JERK "Xジク ヤクド mm/s" // "Vx-jerk"
#define MSG_VY_JERK "Yジク ヤクド mm/s" // "Vy-jerk"
#define MSG_VZ_JERK "Zジク ヤクド mm/s" // "Vz-jerk"
#define MSG_VE_JERK "エクストルーダー ヤクド" // "Ve-jerk"
#define MSG_VMAX "サイダイオクリソクド " // "Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "サイショウオクリソクド" // "Vmin"
#define MSG_VTRAV_MIN "サイショウイドウソクド" // "VTrav min"
#define MSG_AMAX "サイダイカソクド " // "Amax "
@@ -156,6 +151,8 @@
#define MSG_INIT_SDCARD "SDカードサイヨミコミ" // "Init. SD card"
#define MSG_CNG_SDCARD "SDカードコウカン" // "Change SD card"
#define MSG_ZPROBE_OUT "Zプローブ ベッドガイ" // "Z probe out. bed"
#define MSG_BLTOUCH_SELFTEST "BLTouch ジコシンダン" // "BLTouch Self-Test"
#define MSG_BLTOUCH_RESET "BLTouch リセット" // "Reset BLTouch"
#define MSG_HOME "サキニ" // "Home" // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST
#define MSG_FIRST "ヲフッキサセテクダサイ" // "first"
#define MSG_ZPROBE_ZOFFSET "Zオフセット" // "Z Offset"
@@ -170,6 +167,7 @@
#define MSG_ERR_MINTEMP "エラー:サイテイオンミマン" // "Err: MINTEMP"
#define MSG_ERR_MAXTEMP_BED "エラー:ベッド サイコウオンチョウカ" // "Err: MAXTEMP BED"
#define MSG_ERR_MINTEMP_BED "エラー:ベッド サイテイオンミマン" // "Err: MINTEMP BED"
#define MSG_ERR_Z_HOMING MSG_HOME " " MSG_X MSG_Y " " MSG_FIRST // "G28 Z Forbidden"
#define MSG_HALTED "プリンターハテイシシマシタ" // "PRINTER HALTED"
#define MSG_PLEASE_RESET "リセットシテクダサイ" // "Please reset"
#define MSG_SHORT_DAY "d" // One character only
@@ -192,7 +190,9 @@
#define MSG_INFO_EXTRUDERS "エクストルーダースウ" // "Extruders"
#define MSG_INFO_BAUDRATE "ボーレート" // "Baud"
#define MSG_INFO_PROTOCOL "プロトコル" // "Protocol"
#define MSG_INFO_PRINT_COUNT "プリントスウ " // "Print Count"
#define MSG_LIGHTS_ON "キョウタイナイショウメイ オン" // "Case light on"
#define MSG_LIGHTS_OFF "キョウタイナイショウメイ オフ" // "Case light off"
#define MSG_INFO_PRINT_COUNT "プリントスウ " // "Print Count"
#define MSG_INFO_COMPLETED_PRINTS "カンリョウスウ" // "Completed"
#define MSG_INFO_PRINT_TIME "プリントジカンルイケイ" // "Total print time"
#define MSG_INFO_PRINT_LONGEST "サイチョウプリントジカン" // "Longest job time"
@@ -200,6 +200,9 @@
#define MSG_INFO_MIN_TEMP "セッテイサイテイオン" // "Min Temp"
#define MSG_INFO_MAX_TEMP "セッテイサイコウオン" // "Max Temp"
#define MSG_INFO_PSU "デンゲンシュベツ" // "Power Supply"
#define MSG_DRIVE_STRENGTH "モータークドウリョク" // "Drive Strength"
#define MSG_DAC_PERCENT "DACシュツリョク %" // "Driver %"
#define MSG_DAC_EEPROM_WRITE MSG_STORE_EPROM // "DAC EEPROM Write"
#define MSG_FILAMENT_CHANGE_HEADER "フィラメントコウカン" // "CHANGE FILAMENT"
#define MSG_FILAMENT_CHANGE_OPTION_HEADER "ドウサヲセンタクシテクダサイ" // "CHANGE OPTIONS:"
#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "サラニオシダス" // "Extrude more"

View File

@@ -30,8 +30,6 @@
#ifndef LANGUAGE_NL_H
#define LANGUAGE_NL_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " gereed."
@@ -89,14 +87,11 @@
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_ACC "Versn"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "

View File

@@ -30,8 +30,6 @@
#ifndef LANGUAGE_PL_H
#define LANGUAGE_PL_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " gotowy."
@@ -41,7 +39,10 @@
#define MSG_MAIN "Menu glowne"
#define MSG_AUTOSTART "Autostart"
#define MSG_DISABLE_STEPPERS "Wylacz silniki"
#define MSG_AUTO_HOME "Auto. poz. zerowa"
#define MSG_AUTO_HOME "Pozycja zerowa"
#define MSG_AUTO_HOME_X "Home X"
#define MSG_AUTO_HOME_Y "Home Y"
#define MSG_AUTO_HOME_Z "Home Z"
#define MSG_LEVEL_BED_HOMING "Pozycja zerowa"
#define MSG_LEVEL_BED_WAITING "Kliknij by rozp."
#define MSG_LEVEL_BED_NEXT_POINT "Nastepny punkt"
@@ -51,45 +52,33 @@
#define MSG_HOME_OFFSETS_APPLIED "Poz. zerowa ust."
#define MSG_SET_ORIGIN "Ustaw punkt zero"
#define MSG_PREHEAT_1 "Rozgrzej PLA"
#define MSG_PREHEAT_1_N "Rozgrzej PLA "
#define MSG_PREHEAT_1_ALL "Roz. PLA Wszystko"
#define MSG_PREHEAT_1_BEDONLY "Rozgrzej PLA Loze"
#define MSG_PREHEAT_1_N MSG_PREHEAT_1 " "
#define MSG_PREHEAT_1_ALL MSG_PREHEAT_1 " All"
#define MSG_PREHEAT_1_BEDONLY "Rozgrzej stol PLA"
#define MSG_PREHEAT_1_SETTINGS "Ustaw. rozg. PLA"
#define MSG_PREHEAT_2 "Rozgrzej ABS"
#define MSG_PREHEAT_2_N "Rozgrzej ABS "
#define MSG_PREHEAT_2_ALL "Roz. ABS Wszystko"
#define MSG_PREHEAT_2_BEDONLY "Rozgrzej ABS Loze"
#define MSG_PREHEAT_2_N MSG_PREHEAT_2 " "
#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 " All"
#define MSG_PREHEAT_2_BEDONLY "Rozgrzej stol ABS"
#define MSG_PREHEAT_2_SETTINGS "Ustaw. rozg. ABS"
#define MSG_H1 "1"
#define MSG_H2 "2"
#define MSG_H3 "3"
#define MSG_H4 "4"
#define MSG_COOLDOWN "Chlodzenie"
#define MSG_SWITCH_PS_ON "Wlacz zasilacz"
#define MSG_SWITCH_PS_OFF "Wylacz zasilacz"
#define MSG_EXTRUDE "Ekstruzja"
#define MSG_RETRACT "Wycofanie"
#define MSG_MOVE_AXIS "Ruch osi"
#define MSG_LEVEL_BED "Poziom. loza"
#define MSG_LEVEL_BED "Poziom. stolu"
#define MSG_MOVE_X "Przesun w X"
#define MSG_MOVE_Y "Przesun w Y"
#define MSG_MOVE_Z "Przesun w Z"
#define MSG_MOVE_E "Ekstruzja (os E)"
#define MSG_MOVE_E1 "1"
#define MSG_MOVE_E2 "2"
#define MSG_MOVE_E3 "3"
#define MSG_MOVE_E4 "4"
#define MSG_MOVE_01MM "Przesuwaj co .1mm"
#define MSG_MOVE_1MM "Przesuwaj co 1mm"
#define MSG_MOVE_10MM "Przesuwaj co 10mm"
#define MSG_MOVE_01MM "Przesun co .1mm"
#define MSG_MOVE_1MM "Przesun co 1mm"
#define MSG_MOVE_10MM "Przesun co 10mm"
#define MSG_SPEED "Predkosc"
#define MSG_BED_Z "Loze Z"
#define MSG_BED_Z "Stol Z"
#define MSG_NOZZLE "Dysza"
#define MSG_N1 " 1"
#define MSG_N2 " 2"
#define MSG_N3 " 3"
#define MSG_N4 " 4"
#define MSG_BED "Loze"
#define MSG_BED "Stol"
#define MSG_FAN_SPEED "Obroty wiatraka"
#define MSG_FLOW "Przeplyw"
#define MSG_CONTROL "Ustawienia"
@@ -103,19 +92,13 @@
#define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_E1 " E1"
#define MSG_E2 " E2"
#define MSG_E3 " E3"
#define MSG_E4 " E4"
#define MSG_SELECT "Select"
#define MSG_ACC "Przyspieszenie"
#define MSG_VXY_JERK "Zryw Vxy"
#define MSG_VX_JERK "Zryw Vx"
#define MSG_VY_JERK "Zryw Vy"
#define MSG_VZ_JERK "Zryw Vz"
#define MSG_VE_JERK "Zryw Ve"
#define MSG_VMAX "Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "Vskok min"
#define MSG_AMAX "Amax"
@@ -130,10 +113,6 @@
#define MSG_VOLUMETRIC "Filament"
#define MSG_VOLUMETRIC_ENABLED "E w mm3"
#define MSG_FILAMENT_DIAM "Śr. fil."
#define MSG_DIAM_E1 " 1"
#define MSG_DIAM_E2 " 2"
#define MSG_DIAM_E3 " 3"
#define MSG_DIAM_E4 " 4"
#define MSG_CONTRAST "Kontrast LCD"
#define MSG_STORE_EPROM "Zapisz w pamieci"
#define MSG_LOAD_EPROM "Wczytaj z pamieci"
@@ -165,7 +144,9 @@
#define MSG_FILAMENTCHANGE "Zmien filament"
#define MSG_INIT_SDCARD "Inicjal. karty SD"
#define MSG_CNG_SDCARD "Zmiana karty SD"
#define MSG_ZPROBE_OUT "Sonda Z za lozem"
#define MSG_ZPROBE_OUT "Sonda Z za stolem"
#define MSG_BLTOUCH_SELFTEST "BLTouch Self-Test"
#define MSG_BLTOUCH_RESET "Reset BLTouch"
#define MSG_HOME "Home" // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST
#define MSG_FIRST "first"
#define MSG_ZPROBE_ZOFFSET "Offset Z"
@@ -174,20 +155,90 @@
#define MSG_BABYSTEP_Z "Babystep Z"
#define MSG_ENDSTOP_ABORT "Blad krancowki"
#define MSG_HEATING_FAILED_LCD "Rozgrz. nieudane"
#define MSG_ERR_REDUNDANT_TEMP "Błąd temperatury"
#define MSG_ERR_REDUNDANT_TEMP "Blad temperatury"
#define MSG_THERMAL_RUNAWAY "Zanik temp."
#define MSG_ERR_MAXTEMP "Err: max. temp."
#define MSG_ERR_MINTEMP "Err: min. temp."
#define MSG_ERR_MAXTEMP_BED "Err: max. temp. loza"
#define MSG_ERR_MINTEMP_BED "Err: min. temp. loza"
#define MSG_ERR_Z_HOMING "G28 Z Forbidden"
#define MSG_HALTED "PRINTER HALTED"
#define MSG_PLEASE_RESET "Please reset"
#define MSG_SHORT_DAY "d" // One character only
#define MSG_SHORT_HOUR "h" // One character only
#define MSG_SHORT_MINUTE "m" // One character only
#define MSG_HEATING "Rozgrzewanie..."
#define MSG_HEATING_COMPLETE "Rozgrzano"
#define MSG_BED_HEATING "Rozgrzewanie loza..."
#define MSG_BED_DONE "Rozgrzano loze"
#define MSG_BED_HEATING "Rozgrzewanie stolu..."
#define MSG_BED_DONE "Rozgrzano stol"
#define MSG_DELTA_CALIBRATE "Kalibrowanie Delty"
#define MSG_DELTA_CALIBRATE_X "Kalibruj X"
#define MSG_DELTA_CALIBRATE_Y "Kalibruj Y"
#define MSG_DELTA_CALIBRATE_Z "Kalibruj Z"
#define MSG_DELTA_CALIBRATE_CENTER "Kalibruj środek"
#define MSG_INFO_MENU "About Printer"
#define MSG_INFO_PRINTER_MENU "Printer Info"
#define MSG_INFO_STATS_MENU "Printer Stats"
#define MSG_INFO_BOARD_MENU "Board Info"
#define MSG_INFO_THERMISTOR_MENU "Thermistors"
#define MSG_INFO_EXTRUDERS "Extruders"
#define MSG_INFO_BAUDRATE "Baud"
#define MSG_INFO_PROTOCOL "Protocol"
#define MSG_LIGHTS_ON "Case light on"
#define MSG_LIGHTS_OFF "Case light off"
#if LCD_WIDTH >= 20
#define MSG_INFO_PRINT_COUNT "Print Count"
#define MSG_INFO_COMPLETED_PRINTS "Completed"
#define MSG_INFO_PRINT_TIME "Total print time"
#define MSG_INFO_PRINT_LONGEST "Longest job time"
#define MSG_INFO_PRINT_FILAMENT "Extruded total"
#else
#define MSG_INFO_PRINT_COUNT "Prints"
#define MSG_INFO_COMPLETED_PRINTS "Completed"
#define MSG_INFO_PRINT_TIME "Total"
#define MSG_INFO_PRINT_LONGEST "Longest"
#define MSG_INFO_PRINT_FILAMENT "Extruded"
#endif
#define MSG_INFO_MIN_TEMP "Min Temp"
#define MSG_INFO_MAX_TEMP "Max Temp"
#define MSG_INFO_PSU "Power Supply"
#define MSG_DRIVE_STRENGTH "Drive Strength"
#define MSG_DAC_PERCENT "Driver %"
#define MSG_DAC_EEPROM_WRITE "DAC EEPROM Write"
#define MSG_FILAMENT_CHANGE_HEADER "CHANGE FILAMENT"
#define MSG_FILAMENT_CHANGE_OPTION_HEADER "CHANGE OPTIONS:"
#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "Extrude more"
#define MSG_FILAMENT_CHANGE_OPTION_RESUME "Resume print"
#if LCD_HEIGHT >= 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Wait for start"
#define MSG_FILAMENT_CHANGE_INIT_2 "of the filament"
#define MSG_FILAMENT_CHANGE_INIT_3 "change"
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Wait for"
#define MSG_FILAMENT_CHANGE_UNLOAD_2 "filament unload"
#define MSG_FILAMENT_CHANGE_UNLOAD_3 ""
#define MSG_FILAMENT_CHANGE_INSERT_1 "Insert filament"
#define MSG_FILAMENT_CHANGE_INSERT_2 "and press button"
#define MSG_FILAMENT_CHANGE_INSERT_3 "to continue..."
#define MSG_FILAMENT_CHANGE_LOAD_1 "Wait for"
#define MSG_FILAMENT_CHANGE_LOAD_2 "filament load"
#define MSG_FILAMENT_CHANGE_LOAD_3 ""
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Wait for"
#define MSG_FILAMENT_CHANGE_EXTRUDE_2 "filament extrude"
#define MSG_FILAMENT_CHANGE_EXTRUDE_3 ""
#define MSG_FILAMENT_CHANGE_RESUME_1 "Wait for print"
#define MSG_FILAMENT_CHANGE_RESUME_2 "to resume"
#define MSG_FILAMENT_CHANGE_RESUME_3 ""
#else // LCD_HEIGHT < 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Please wait..."
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Ejecting..."
#define MSG_FILAMENT_CHANGE_INSERT_1 "Insert and Click"
#define MSG_FILAMENT_CHANGE_LOAD_1 "Loading..."
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Extruding..."
#define MSG_FILAMENT_CHANGE_RESUME_1 "Resuming..."
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_PL_H

View File

@@ -30,8 +30,6 @@
#ifndef LANGUAGE_PT_BR_H
#define LANGUAGE_PT_BR_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " pronto."
@@ -89,14 +87,11 @@
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_ACC "Acc"
#define MSG_VXY_JERK "jogo VXY"
#define MSG_VX_JERK "jogo VX"
#define MSG_VY_JERK "jogo VY"
#define MSG_VZ_JERK "jogo VZ"
#define MSG_VE_JERK "jogo VE"
#define MSG_VMAX " Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "

View File

@@ -30,8 +30,6 @@
#ifndef LANGUAGE_PT_BR_UTF_H
#define LANGUAGE_PT_BR_UTF_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " pronto."
@@ -89,14 +87,11 @@
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_ACC "Acc"
#define MSG_VXY_JERK "jogo VXY"
#define MSG_VX_JERK "jogo VX"
#define MSG_VY_JERK "jogo VY"
#define MSG_VZ_JERK "jogo VZ"
#define MSG_VE_JERK "jogo VE"
#define MSG_VMAX " Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "

View File

@@ -30,8 +30,6 @@
#ifndef LANGUAGE_PT_H
#define LANGUAGE_PT_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " pronto."
@@ -92,19 +90,12 @@
#define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_E1 "E1"
#define MSG_E2 "E2"
#define MSG_E3 "E3"
#define MSG_E4 "E4"
#define MSG_ACC "Acc"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX " Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "

View File

@@ -30,8 +30,6 @@
#ifndef LANGUAGE_PT_UTF_H
#define LANGUAGE_PT_UTF_H
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " pronto."
@@ -92,19 +90,12 @@
#define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_E1 "E1"
#define MSG_E2 "E2"
#define MSG_E3 "E3"
#define MSG_E4 "E4"
#define MSG_ACC "Acc"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VX_JERK "Vx-jerk"
#define MSG_VY_JERK "Vy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX " Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "

View File

@@ -31,23 +31,23 @@
#define LANGUAGE_RU_H
#define MAPPER_D0D1 // For Cyrillic
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_5
#define WELCOME_MSG MACHINE_NAME " Готов."
#define MSG_SD_INSERTED "Карта вставлена"
#define MSG_SD_REMOVED "Карта извлечена"
#define MSG_MAIN "Меню"
#define MSG_LCD_ENDSTOPS "концевик"
#define MSG_AUTOSTART "Автостарт"
#define MSG_DISABLE_STEPPERS "Выкл. двигатели"
#define MSG_AUTO_HOME "Парковка"
#define MSG_LEVEL_BED_HOMING "Homing XYZ"
#define MSG_LEVEL_BED_WAITING "Click to Begin"
#define MSG_LEVEL_BED_DONE "Leveling Done!"
#define MSG_LEVEL_BED_CANCEL "Cancel"
#define MSG_LEVEL_BED_HOMING "Нулевое полож"
#define MSG_LEVEL_BED_WAITING "Нажмите начать"
#define MSG_LEVEL_BED_NEXT_POINT "Следующая точка"
#define MSG_LEVEL_BED_DONE "Уровень!"
#define MSG_LEVEL_BED_CANCEL "Отменить"
#define MSG_SET_HOME_OFFSETS "Запомнить парковку"
#define MSG_HOME_OFFSETS_APPLIED "Offsets applied"
#define MSG_HOME_OFFSETS_APPLIED "Коррекции примен"
#define MSG_SET_ORIGIN "Запомнить ноль"
#define MSG_PREHEAT_1 "Преднагрев PLA"
#define MSG_PREHEAT_1_N "Греть PLA Сопло "
@@ -65,6 +65,7 @@
#define MSG_EXTRUDE "Экструзия"
#define MSG_RETRACT "Втягивание"
#define MSG_MOVE_AXIS "Движение по осям"
#define MSG_LEVEL_BED "Калибровать стол"
#define MSG_MOVE_X "Движение по X"
#define MSG_MOVE_Y "Движение по Y"
#define MSG_MOVE_Z "Движение по Z"
@@ -72,8 +73,8 @@
#define MSG_MOVE_01MM "Движение XYZ 0.1mm"
#define MSG_MOVE_1MM "Движение XYZ 1mm"
#define MSG_MOVE_10MM "Движение XY 10mm"
#define MSG_LEVEL_BED "Калибровать стол"
#define MSG_SPEED "Скорость"
#define MSG_BED_Z "Z стола"
#define MSG_NOZZLE LCD_STR_THERMOMETER " Сопло"
#define MSG_BED LCD_STR_THERMOMETER " Стол"
#define MSG_FAN_SPEED "Кулер"
@@ -90,18 +91,16 @@
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_ACC "Acc"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "X"
#define MSG_Y "Y"
#define MSG_Z "Z"
#define MSG_E "E"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax"
#define MSG_VX_JERK "Vx-рывок"
#define MSG_VY_JERK "Vy-рывок"
#define MSG_VZ_JERK "Vz-рывок"
#define MSG_VE_JERK "Ve-рывок"
#define MSG_VMAX "Vмакс "
#define MSG_VMIN "Vмин"
#define MSG_VTRAV_MIN "Vпутеш. мин"
#define MSG_AMAX "акс"
#define MSG_A_RETRACT "A-втягивание"
#define MSG_A_TRAVEL "A-путеш."
#define MSG_XSTEPS "X шаг/мм"
#define MSG_YSTEPS "Y шаг/мм"
#define MSG_ZSTEPS "Z шаг/мм"
@@ -143,15 +142,16 @@
#define MSG_INIT_SDCARD "Иниц. карту"
#define MSG_CNG_SDCARD "Сменить карту"
#define MSG_ZPROBE_OUT "Z датчик вне стола"
#define MSG_YX_UNHOMED "Паркуй X/Y перед Z"
#define MSG_HOME "Паркуй X/Y перед Z"
#define MSG_FIRST "первый"
#define MSG_ZPROBE_ZOFFSET "Смещение Z"
#define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_Y "Babystep Y"
#define MSG_BABYSTEP_Z "Babystep Z"
#define MSG_BABYSTEP_X "Микрошаг X"
#define MSG_BABYSTEP_Y "Микрошаг Y"
#define MSG_BABYSTEP_Z "Микрошаг Z"
#define MSG_ENDSTOP_ABORT "Сработал концевик"
#define MSG_HEATING_FAILED_LCD "Разогрев не удался"
#define MSG_ERR_REDUNDANT_TEMP "Ошибка:Слишком горячо"
#define MSG_THERMAL_RUNAWAY "THERMAL RUNAWAY"
#define MSG_THERMAL_RUNAWAY "ТЕПЛО УБЕГАНИЯ!"
#define MSG_ERR_MAXTEMP "Ошибка: Т макс."
#define MSG_ERR_MINTEMP "Ошибка: Т мин."
#define MSG_ERR_MAXTEMP_BED "Ошибка:Т макс.стол"
@@ -164,6 +164,6 @@
#define MSG_DELTA_CALIBRATE_X "Калибровать X"
#define MSG_DELTA_CALIBRATE_Y "Калибровать Y"
#define MSG_DELTA_CALIBRATE_Z "Калибровать Z"
#define MSG_DELTA_CALIBRATE_CENTER "Калибровать Center"
#define MSG_DELTA_CALIBRATE_CENTER "Калибровать центр"
#endif // LANGUAGE_RU_H

View File

@@ -51,8 +51,6 @@
//#define MAPPER_E382E383 // For Katakana
//#define MAPPER_NON // For direct ascii codes. Fall back mapper - if no other is defined.
// Define SIMULATE_ROMFONT to see what is seen on the character based display defined in Configuration.h
//#define SIMULATE_ROMFONT
// Select the better font for full graphic displays.
//#define DISPLAY_CHARSET_ISO10646_1

243
Marlin/language_tr.h Normal file
View File

@@ -0,0 +1,243 @@
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/**
* Turkish
*
* LCD Menu Messages
* See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language
*
*/
#ifndef LANGUAGE_TR_H
#define LANGUAGE_TR_H
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_TR
#define WELCOME_MSG MACHINE_NAME " haz\xfdr." //hazır.
#define MSG_SD_INSERTED "SD Yerle\xfeti." //SD Yerleşti.
#define MSG_SD_REMOVED "SD \xc7\xfdkar\xfdld\xfd." //SD Çıkarıldı.
#define MSG_LCD_ENDSTOPS "Endstops" // Max length 8 characters //Endstops
#define MSG_MAIN "Ana" //Ana
#define MSG_AUTOSTART "Otoba\xfelat" //Otobaşlat
#define MSG_DISABLE_STEPPERS "Motorlar\xfd Durdur" //Motorları Durdur
#define MSG_AUTO_HOME "Eksenleri S\xfd\x66\xfdrla" //Eksenleri Sıfırla
#define MSG_AUTO_HOME_X "X S\xfd\x66\xfdrla" //X Sıfırla
#define MSG_AUTO_HOME_Y "Y S\xfd\x66\xfdrla" //Y Sıfırla
#define MSG_AUTO_HOME_Z "Z S\xfd\x66\xfdrla" //Z Sıfırla
#define MSG_LEVEL_BED_HOMING "XYZ S\xfd\x66\xfdrlan\xfdyor" //XYZ Sıfırlanıyor
#define MSG_LEVEL_BED_WAITING "Ba\xfelatmak i\xe7in t\xfdkla" //Başlatmak için tıkla
#define MSG_LEVEL_BED_NEXT_POINT "S\xfdradaki Nokta" //Sıradaki Nokta
#define MSG_LEVEL_BED_DONE "Seviyeleme Tamam!" //Seviyeleme Tamam!
#define MSG_LEVEL_BED_CANCEL "\xddptal" //İptal
#define MSG_SET_HOME_OFFSETS "Offset Ayarla" //Offset Ayarla
#define MSG_HOME_OFFSETS_APPLIED "Offset Tamam" //Offset Tamam
#define MSG_SET_ORIGIN "S\xfd\x66\xfdr Belirle" //Sıfır Belirle
#define MSG_PREHEAT_1 "\xd6n Is\xfdnma PLA" //Ön Isınma PLA
#define MSG_PREHEAT_1_N MSG_PREHEAT_1 " " //
#define MSG_PREHEAT_1_ALL MSG_PREHEAT_1 " T\xfcm" // Tüm
#define MSG_PREHEAT_1_BEDONLY MSG_PREHEAT_1 " Tabla" // Tabla
#define MSG_PREHEAT_1_SETTINGS MSG_PREHEAT_1 " Ayar" // Ayar
#define MSG_PREHEAT_2 "\xd6n Is\xfdnma ABS" //Ön Isınma ABS
#define MSG_PREHEAT_2_N MSG_PREHEAT_2 " " //
#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 " T\xfcm" // Tüm
#define MSG_PREHEAT_2_BEDONLY MSG_PREHEAT_2 " Tabla" // Tabla
#define MSG_PREHEAT_2_SETTINGS MSG_PREHEAT_2 " Ayar" // Ayar
#define MSG_COOLDOWN "So\xf0ut" //Soğut
#define MSG_SWITCH_PS_ON "G\xfcc\xfc A\xe7" //Gücü Aç
#define MSG_SWITCH_PS_OFF "G\xfcc\xfc Kapat" //Gücü Kapat
#define MSG_EXTRUDE "Extrude" //Extrude
#define MSG_RETRACT "Geri \xc7ek" //Geri Çek
#define MSG_MOVE_AXIS "Eksen Y\xf6net" //Eksenleri Yönet
#define MSG_LEVEL_BED "Tabla Seviyele" //Tabla Seviyele
#define MSG_MOVE_X "X" //X
#define MSG_MOVE_Y "Y" //Y
#define MSG_MOVE_Z "Z" //Z
#define MSG_MOVE_E "Ekstruder" //Ekstruder
#define MSG_MOVE_01MM "0.1mm" //0.1mm
#define MSG_MOVE_1MM "1mm" //1mm
#define MSG_MOVE_10MM "10mm" //10mm
#define MSG_SPEED "H\xfdz" //Hız
#define MSG_BED_Z "Tabla Z" //Tabla Z
#define MSG_NOZZLE "Noz\xfcl" //Nozül
#define MSG_BED "Tabla" //Tabla
#define MSG_FAN_SPEED "Fan H\xfdz\xfd" //Fan Hızı
#define MSG_FLOW "Ak\xfd\xfe" //Akış
#define MSG_CONTROL "Kontrol" //Kontrol
#define MSG_MIN " " LCD_STR_THERMOMETER " Min" // Min
#define MSG_MAX " " LCD_STR_THERMOMETER " Max" // Max
#define MSG_FACTOR " " LCD_STR_THERMOMETER " \xc7\x61rpan" // Çarpan
#define MSG_AUTOTEMP "Autotemp" // Autotemp
#define MSG_ON "On " //On
#define MSG_OFF "Off" //Off
#define MSG_PID_P "PID-P" //PID-P
#define MSG_PID_I "PID-I" //PID-I
#define MSG_PID_D "PID-D" //PID-D
#define MSG_PID_C "PID-C" //PID-C
#define MSG_SELECT "Se\xe7" //Seç
#define MSG_ACC "\xddvme" //İvme
#define MSG_VX_JERK "Vx-Jerk" //Vx-Jerk
#define MSG_VY_JERK "Vy-Jerk" //Vy-Jerk
#define MSG_VZ_JERK "Vz-jerk" //Vz-Jerk
#define MSG_VE_JERK "Ve-jerk" //Ve-Jerk
#define MSG_VMAX "Vmax " //Vmax
#define MSG_VMIN "Vmin" //Vmin
#define MSG_VTRAV_MIN "VTrav min" //Vtrav min
#define MSG_AMAX "Amax " //Amax
#define MSG_A_RETRACT "A-retract" //A-retract
#define MSG_A_TRAVEL "A-travel" //A-travel
#define MSG_XSTEPS "Xsteps/mm" //Xsteps/mm
#define MSG_YSTEPS "Ysteps/mm" //Ysteps/mm
#define MSG_ZSTEPS "Zsteps/mm" //Zsteps/mm
#define MSG_ESTEPS "Esteps/mm" //Esteps/mm
#define MSG_TEMPERATURE "S\xfd\x63\x61kl\xfdk" //Sıcaklık
#define MSG_MOTION "Hareket" //Hareket
#define MSG_VOLUMETRIC "Filaman" //Filaman
#define MSG_VOLUMETRIC_ENABLED "E in mm3" //E in mm3
#define MSG_FILAMENT_DIAM "Fil. \xc7\x61p" //Fil. Çap
#define MSG_CONTRAST "LCD Kontrast" //LCD Kontrast
#define MSG_STORE_EPROM "Haf\xfdzaya Al" //Hafızaya Al
#define MSG_LOAD_EPROM "Haf\xfdzadan Y\xfckle" //Hafızadan Yükle
#define MSG_RESTORE_FAILSAFE "Fabrika Ayarlar\xfd" //Fabrika Ayarları
#define MSG_REFRESH "Yenile" //Yenile
#define MSG_WATCH "Bilgi Ekran\xfd" //Bilgi Ekranı
#define MSG_PREPARE "Haz\xfdrl\xfdk" //Hazırlık
#define MSG_TUNE "Ayar" //Ayar
#define MSG_PAUSE_PRINT "Duraklat" //Duraklat
#define MSG_RESUME_PRINT "S\xfcrd\xfcr" //Sürdür
#define MSG_STOP_PRINT "Durdur" //Durdur
#define MSG_CARD_MENU "SD den Yazd\xfdr" //SD den Yazdır
#define MSG_NO_CARD "SD Kart Yok" //SD Kart Yok
#define MSG_DWELL "Uyku..." //Uyku...
#define MSG_USERWAIT "Operat\xf6r bekleniyor..." //Operatör bekleniyor...
#define MSG_RESUMING "Bask\xfd S\xfcrd\xfcr\xfcl\xfcyor" //Baskı Sürdürülüyor
#define MSG_PRINT_ABORTED "Bask\xfd Durduruldu" //Baskı Durduruldu
#define MSG_NO_MOVE "\xdd\xfelem yok." //İşlem yok.
#define MSG_KILLED "Kilitlendi. " //Kilitlendi.
#define MSG_STOPPED "Durdu. " //Durdu.
#define MSG_CONTROL_RETRACT "Geri \xc7ek mm" //Geri Çek mm
#define MSG_CONTROL_RETRACT_SWAP "Swap Re.mm" //Swap Re.mm
#define MSG_CONTROL_RETRACTF "Geri \xc7ekme V" //Geri Çekme V
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm" //Hop mm
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm" //UnRet +mm
#define MSG_CONTROL_RETRACT_RECOVER_SWAP "S UnRet+mm" //S UnRet+mm
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet V" //UnRet V
#define MSG_AUTORETRACT "AutoRetr." //AutoRetr.
#define MSG_FILAMENTCHANGE "Filaman De\xf0i\xfetir" //Filaman Değiştir
#define MSG_INIT_SDCARD "Init. SD" //Init. SD
#define MSG_CNG_SDCARD "SD De\xf0i\xfetir" //SD Değiştir
#define MSG_ZPROBE_OUT "Z Prob A\xe7\xfdk. Tabla" //Z Prob Açık. Tabla
#define MSG_BLTOUCH_SELFTEST "BLTouch Self-Test" //BLTouch Self-Test
#define MSG_BLTOUCH_RESET "S\xfd\x66\xfdrla BLTouch" //Sıfırla BLTouch
#define MSG_HOME "S\xfd\x66\xfdrla" //Sıfırla
#define MSG_FIRST "\xf6nce" //Önce
#define MSG_ZPROBE_ZOFFSET "Z Offset" //Z Offset
#define MSG_BABYSTEP_X "Miniad\xfdm X" //Miniadım X
#define MSG_BABYSTEP_Y "Miniad\xfdm Y" //Miniadım Y
#define MSG_BABYSTEP_Z "Miniad\xfdm Z" //Miniadım Z
#define MSG_ENDSTOP_ABORT "Endstop iptal" //Endstop iptal
#define MSG_HEATING_FAILED_LCD "Is\xfdnma ba\xfe\x61\x72\xfds\xfdz" //Isınma başarısız
#define MSG_ERR_REDUNDANT_TEMP "Hata: Ge\xe7ersiz S\xfd\x63akl\xfdk" //Hata: Geçersiz Sıcaklık
#define MSG_THERMAL_RUNAWAY "TERMAL PROBLEM" //TERMAL PROBLEM
#define MSG_ERR_MAXTEMP "Hata: MAXSICAKLIK" //Hata: MAXSICAKLIK
#define MSG_ERR_MINTEMP "Hata: MINSICAKLIK" //Hata: MINSICAKLIK
#define MSG_ERR_MAXTEMP_BED "Hata: MAXSIC. TABLA" //Hata: MAXSIC. TABLA
#define MSG_ERR_MINTEMP_BED "Hata: MINSIC. TABLA" //Hata: MINSIC. TABLA
#define MSG_ERR_Z_HOMING "G28 Z Yap\xfdlamaz" //G28 Z Yapılamaz
#define MSG_HALTED "YAZICI DURDURULDU" //YAZICI DURDURULDU
#define MSG_PLEASE_RESET "L\xfctfen resetleyin" //Lütfen resetleyin
#define MSG_SHORT_DAY "G" // One character only //G
#define MSG_SHORT_HOUR "S" // One character only //S
#define MSG_SHORT_MINUTE "D" // One character only //D
#define MSG_HEATING "Is\xfdn\xfdyor..." //Isınıyor...
#define MSG_HEATING_COMPLETE "Is\xfdnma tamam." //Isınma tamam.
#define MSG_BED_HEATING "Tabla Is\xfdn\xfdyor." //Tabla Isınıyor.
#define MSG_BED_DONE "Tabla haz\xfdr." //Tabla hazır.
#define MSG_DELTA_CALIBRATE "Delta Kalibrasyonu" //Delta Kalibrasyonu
#define MSG_DELTA_CALIBRATE_X "Ayarla X" //Ayarla X
#define MSG_DELTA_CALIBRATE_Y "Ayarla Y" //Ayarla Y
#define MSG_DELTA_CALIBRATE_Z "Ayarla Z" //Ayarla Z
#define MSG_DELTA_CALIBRATE_CENTER "Ayarla Merkez" //Ayarla Merkez
#define MSG_INFO_MENU "Yaz\xfd\x63\xfd Hakk\xfdnda" //Yazıcı Hakkında
#define MSG_INFO_PRINTER_MENU "Yaz\xfd\x63\xfd Bilgisi" //Yazıcı Bilgisi
#define MSG_INFO_STATS_MENU "\xddstatistikler" //İstatistikler
#define MSG_INFO_BOARD_MENU "Kontrol\xf6r Bilgisi" //Kontrol Bilgisi
#define MSG_INFO_THERMISTOR_MENU "Termist\xf6rler" //Termistörler
#define MSG_INFO_EXTRUDERS "Ekstruderler" //Ekstruderler
#define MSG_INFO_BAUDRATE "\xddleti\xfeim H\xfdz\xfd" //İletişim Hızı
#define MSG_INFO_PROTOCOL "Protokol" //Protokol
#if LCD_WIDTH > 19
#define MSG_INFO_PRINT_COUNT "Bask\xfd Say\xfds\xfd" //Baskı Sayısı
#define MSG_INFO_COMPLETED_PRINTS "Tamamlanan" //Tamamlanan
#define MSG_INFO_PRINT_TIME "Toplam Bask\xfd S\xfcresi" //Toplam Baskı Süresi
#define MSG_INFO_PRINT_LONGEST "En Uzun Bask\xfd S\xfcresi" //En Uzun Baskı Süresi
#define MSG_INFO_PRINT_FILAMENT "Toplam Filaman" //Toplam Filaman
#else
#define MSG_INFO_PRINT_COUNT "Bask\xfd" //Baskı
#define MSG_INFO_COMPLETED_PRINTS "Tamamlanan" //Tamamlanan
#define MSG_INFO_PRINT_TIME "S\xfcre" //Süre
#define MSG_INFO_PRINT_LONGEST "En Uzun" //En Uzun
#define MSG_INFO_PRINT_FILAMENT "Filaman" //Filaman
#endif
#define MSG_INFO_MIN_TEMP "Min S\xfd\x63." //Min Sıcak.
#define MSG_INFO_MAX_TEMP "Max S\xfd\x63." //Max Sıcak.
#define MSG_INFO_PSU "G\xfc\xe7 Kayna\xf0\xfd" //Güç Kaynağı
#define MSG_DRIVE_STRENGTH "\x53\xfc\x72\xfc\x63\xfc \x47\xfc\x63\xfc" //Sürücü Gücü
#define MSG_DAC_PERCENT "\x53\xfc\x72\xfc\x63\xfc %" //Sürücü %
#define MSG_DAC_EEPROM_WRITE "DAC\x27\xfd EEPROM\x27\x61 Yaz" //DAC'ı EEPROM'a Yaz
#define MSG_FILAMENT_CHANGE_HEADER "Filaman De\xf0i\xfetir" //Filaman Değiştir
#define MSG_FILAMENT_CHANGE_OPTION_HEADER "Se\xe7enekler:" //Seçenekler:
#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "Daha Ak\xfdt" //Daha Akıt
#define MSG_FILAMENT_CHANGE_OPTION_RESUME "Bask\xfdy\xfd s\xfcrd\xfcr" //Baskıyı sürdür
#if LCD_HEIGHT >= 4
#define MSG_FILAMENT_CHANGE_INIT_1 "Ba\xfelama bekleniyor" //Başlama bekleniyor
#define MSG_FILAMENT_CHANGE_INIT_2 "filaman\xfdn" //filamanın
#define MSG_FILAMENT_CHANGE_INIT_3 "de\xf0i\xfeimi" //değişimi
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "Bekleniyor" //Bekleniyor
#define MSG_FILAMENT_CHANGE_UNLOAD_2 "filaman\xfdn \xe7\xfdkmas\xfd" //filamanın çıkması
#define MSG_FILAMENT_CHANGE_UNLOAD_3 "" //
#define MSG_FILAMENT_CHANGE_INSERT_1 "Filaman\xfd y\xfckle" //Filamanı yükle
#define MSG_FILAMENT_CHANGE_INSERT_2 "ve devam i\xe7in" //ve devam için
#define MSG_FILAMENT_CHANGE_INSERT_3 "tu\xfea bas..." //tuşa bas...
#define MSG_FILAMENT_CHANGE_LOAD_1 "Bekleniyor" //Bekleniyor
#define MSG_FILAMENT_CHANGE_LOAD_2 "filaman\xfdn y\xfcklenmesi" //filamanın yüklenmesi
#define MSG_FILAMENT_CHANGE_LOAD_3 "" //
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Bekleniyor" //Bekleniyor
#define MSG_FILAMENT_CHANGE_EXTRUDE_2 "filaman akmas\xfd" //filaman akması
#define MSG_FILAMENT_CHANGE_EXTRUDE_3 "" //
#define MSG_FILAMENT_CHANGE_RESUME_1 "Bask\xfdn\xfdn s\xfcrd\xfcr\xfclmesini" //Baskının sürdürülmesini
#define MSG_FILAMENT_CHANGE_RESUME_2 "bekle" //bekle
#define MSG_FILAMENT_CHANGE_RESUME_3 "" //
#else // LCD_HEIGHT < 4
#define MSG_FILAMENT_CHANGE_INIT_1 "L\xfctfen bekleyiniz..." //Lütfen bekleyiniz...
#define MSG_FILAMENT_CHANGE_UNLOAD_1 "\xc7\xfdkart\xfdl\xfdyor..." //Çıkartılıyor...
#define MSG_FILAMENT_CHANGE_INSERT_1 "Y\xfckle ve bas" //Yükle ve bas
#define MSG_FILAMENT_CHANGE_LOAD_1 "Y\xfckl\xfcyor..." //Yüklüyor...
#define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Ak\xfdt\xfdl\xfdyor..." //Akıtılıyor...
#define MSG_FILAMENT_CHANGE_RESUME_1 "S\xfcrd\xfcr\xfcl\xfcyor..." //Sürdürülüyor...
#endif // LCD_HEIGHT < 4
#endif // LANGUAGE_TR_H

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