diff --git a/.gitignore b/.gitignore old mode 100644 new mode 100755 index 1e87012533..cfbb87385b --- a/.gitignore +++ b/.gitignore @@ -114,3 +114,7 @@ applet/ # Debug files *.dSYM/ *.su + +#PlatformIO files/dirs +.pioenvs +.piolib diff --git a/.travis.yml b/.travis.yml index 23d673f4b2..6d1a2f97e6 100644 --- a/.travis.yml +++ b/.travis.yml @@ -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 diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 29c67bf757..8418385026 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -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 diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index aa6b28a505..709e87e645 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -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 diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index ad869b712e..5565afb3b1 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index a822c83b11..41fd8b4c5f 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/Makefile b/Marlin/Makefile index 1328053543..81eeceada9 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -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 $<" diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index 9f289f208b..0c3511ad7c 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -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 diff --git a/Marlin/Marlin.ino b/Marlin/Marlin.ino index 70fd8adfc2..c2654c09a5 100644 --- a/Marlin/Marlin.ino +++ b/Marlin/Marlin.ino @@ -67,6 +67,11 @@ #include #endif +#if ENABLED(HAVE_TMC2130DRIVER) + #include + #include +#endif + #if ENABLED(HAVE_L6470DRIVER) #include #include diff --git a/Marlin/MarlinSerial.cpp b/Marlin/MarlinSerial.cpp index 9ef900265b..682c73048a 100644 --- a/Marlin/MarlinSerial.cpp +++ b/Marlin/MarlinSerial.cpp @@ -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 diff --git a/Marlin/MarlinSerial.h b/Marlin/MarlinSerial.h index e761752284..87f4f6a92b 100644 --- a/Marlin/MarlinSerial.h +++ b/Marlin/MarlinSerial.h @@ -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; diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp old mode 100644 new mode 100755 index d1c4876f1c..9e6c09c681 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -21,7 +21,6 @@ */ /** - * * About Marlin * * This firmware is a mashup between Sprinter and grbl. @@ -32,23 +31,194 @@ * - http://reprap.org/pipermail/reprap-dev/2011-May/003323.html */ +/** + * ----------------- + * G-Codes in Marlin + * ----------------- + * + * Helpful G-code references: + * - http://linuxcnc.org/handbook/gcode/g-code.html + * - http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes + * + * Help to document Marlin's G-codes online: + * - http://reprap.org/wiki/G-code + * - https://github.com/MarlinFirmware/MarlinDocumentation + * + * ----------------- + * + * "G" Codes + * + * G0 -> G1 + * G1 - Coordinated Movement X Y Z E + * G2 - CW ARC + * G3 - CCW ARC + * G4 - Dwell S or P + * G5 - Cubic B-spline with XYZE destination and IJPQ offsets + * G10 - Retract filament according to settings of M207 + * G11 - Retract recover filament according to settings of M208 + * G12 - Clean tool + * G20 - Set input units to inches + * G21 - Set input units to millimeters + * G28 - Home one or more axes + * G29 - Detailed Z probe, probes the bed at 3 or more points. Will fail if you haven't homed yet. + * G30 - Single Z probe, probes bed at X Y location (defaults to current XY location) + * G31 - Dock sled (Z_PROBE_SLED only) + * G32 - Undock sled (Z_PROBE_SLED only) + * G38 - Probe target - similar to G28 except it uses the Z_MIN endstop for all three axes + * G90 - Use Absolute Coordinates + * G91 - Use Relative Coordinates + * G92 - Set current position to coordinates given + * + * "M" Codes + * + * M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled) + * M1 - Same as M0 + * M17 - Enable/Power all stepper motors + * M18 - Disable all stepper motors; same as M84 + * M20 - List SD card. (Requires SDSUPPORT) + * M21 - Init SD card. (Requires SDSUPPORT) + * M22 - Release SD card. (Requires SDSUPPORT) + * M23 - Select SD file: "M23 /path/file.gco". (Requires SDSUPPORT) + * M24 - Start/resume SD print. (Requires SDSUPPORT) + * M25 - Pause SD print. (Requires SDSUPPORT) + * M26 - Set SD position in bytes: "M26 S12345". (Requires SDSUPPORT) + * M27 - Report SD print status. (Requires SDSUPPORT) + * M28 - Start SD write: "M28 /path/file.gco". (Requires SDSUPPORT) + * M29 - Stop SD write. (Requires SDSUPPORT) + * M30 - Delete file from SD: "M30 /path/file.gco" + * M31 - Report time since last M109 or SD card start to serial. + * M32 - Select file and start SD print: "M32 [S] !/path/file.gco#". (Requires SDSUPPORT) + * Use P to run other files as sub-programs: "M32 P !filename#" + * The '#' is necessary when calling from within sd files, as it stops buffer prereading + * M33 - Get the longname version of a path. (Requires LONG_FILENAME_HOST_SUPPORT) + * M42 - Change pin status via gcode: M42 P S. LED pin assumed if P is omitted. + * M43 - Monitor pins & report changes - report active pins + * M48 - Measure Z Probe repeatability: M48 P X Y V E L. (Requires Z_MIN_PROBE_REPEATABILITY_TEST) + * M75 - Start the print job timer. + * M76 - Pause the print job timer. + * M77 - Stop the print job timer. + * M78 - Show statistical information about the print jobs. (Requires PRINTCOUNTER) + * M80 - Turn on Power Supply. (Requires POWER_SUPPLY) + * M81 - Turn off Power Supply. (Requires POWER_SUPPLY) + * M82 - Set E codes absolute (default). + * M83 - Set E codes relative while in Absolute (G90) mode. + * M84 - Disable steppers until next move, or use S to specify an idle + * duration after which steppers should turn off. S0 disables the timeout. + * M85 - Set inactivity shutdown timer with parameter S. To disable set zero (default) + * M92 - Set planner.axis_steps_per_mm for one or more axes. + * M104 - Set extruder target temp. + * M105 - Report current temperatures. + * M106 - Fan on. + * M107 - Fan off. + * M108 - Break out of heating loops (M109, M190, M303). With no controller, breaks out of M0/M1. (Requires EMERGENCY_PARSER) + * M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating + * Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling + * If AUTOTEMP is enabled, S B F. Exit autotemp by any M109 without F + * M110 - Set the current line number. (Used by host printing) + * M111 - Set debug flags: "M111 S". See flag bits defined in enum.h. + * M112 - Emergency stop. + * M113 - Get or set the timeout interval for Host Keepalive "busy" messages. (Requires HOST_KEEPALIVE_FEATURE) + * M114 - Report current position. + * M115 - Report capabilities. (Extended capabilities requires EXTENDED_CAPABILITIES_REPORT) + * M117 - Display a message on the controller screen. (Requires an LCD) + * M119 - Report endstops status. + * M120 - Enable endstops detection. + * M121 - Disable endstops detection. + * M126 - Solenoid Air Valve Open. (Requires BARICUDA) + * M127 - Solenoid Air Valve Closed. (Requires BARICUDA) + * M128 - EtoP Open. (Requires BARICUDA) + * M129 - EtoP Closed. (Requires BARICUDA) + * M140 - Set bed target temp. S + * M145 - Set heatup values for materials on the LCD. H B F for S (0=PLA, 1=ABS) + * M149 - Set temperature units. (Requires TEMPERATURE_UNITS_SUPPORT) + * M150 - Set Status LED Color as R U B. Values 0-255. (Requires BLINKM or RGB_LED) + * M155 - Auto-report temperatures with interval of S. (Requires AUTO_REPORT_TEMPERATURES) + * M163 - Set a single proportion for a mixing extruder. (Requires MIXING_EXTRUDER) + * M164 - Save the mix as a virtual extruder. (Requires MIXING_EXTRUDER and MIXING_VIRTUAL_TOOLS) + * M165 - Set the proportions for a mixing extruder. Use parameters ABCDHI to set the mixing factors. (Requires MIXING_EXTRUDER) + * M190 - Sxxx Wait for bed current temp to reach target temp. ** Waits only when heating! ** + * Rxxx Wait for bed current temp to reach target temp. ** Waits for heating or cooling. ** + * M200 - Set filament diameter, D, setting E axis units to cubic. (Use S0 to revert to linear units.) + * M201 - Set max acceleration in units/s^2 for print moves: "M201 X Y Z E" + * M202 - Set max acceleration in units/s^2 for travel moves: "M202 X Y Z E" ** UNUSED IN MARLIN! ** + * M203 - Set maximum feedrate: "M203 X Y Z E" in units/sec. + * M204 - Set default acceleration in units/sec^2: P R T + * M205 - Set advanced settings. Current units apply: + S T minimum speeds + B + X, Y, Z, E + * M206 - Set additional homing offset. + * M207 - Set Retract Length: S, Feedrate: F, and Z lift: Z. (Requires FWRETRACT) + * M208 - Set Recover (unretract) Additional (!) Length: S and Feedrate: F. (Requires FWRETRACT) + * M209 - Turn Automatic Retract Detection on/off: S<0|1> (For slicers that don't support G10/11). (Requires FWRETRACT) + Every normal extrude-only move will be classified as retract depending on the direction. + * M211 - Enable, Disable, and/or Report software endstops: S<0|1> + * M218 - Set a tool offset: "M218 T X Y". (Requires 2 or more extruders) + * M220 - Set Feedrate Percentage: "M220 S" (i.e., "FR" on the LCD) + * M221 - Set Flow Percentage: "M221 S" + * M226 - Wait until a pin is in a given state: "M226 P S" + * M240 - Trigger a camera to take a photograph. (Requires CHDK or PHOTOGRAPH_PIN) + * M250 - Set LCD contrast: "M250 C" (0-63). (Requires LCD support) + * M260 - i2c Send Data (Requires EXPERIMENTAL_I2CBUS) + * M261 - i2c Request Data (Requires EXPERIMENTAL_I2CBUS) + * M280 - Set servo position absolute: "M280 P S". (Requires servos) + * M300 - Play beep sound S P + * M301 - Set PID parameters P I and D. (Requires PIDTEMP) + * M302 - Allow cold extrudes, or set the minimum extrude S. (Requires PREVENT_COLD_EXTRUSION) + * M303 - PID relay autotune S sets the target temperature. Default 150C. (Requires PIDTEMP) + * M304 - Set bed PID parameters P I and D. (Requires PIDTEMPBED) + * M355 - Turn the Case Light on/off and set its brightness. (Requires CASE_LIGHT_PIN) + * M380 - Activate solenoid on active extruder. (Requires EXT_SOLENOID) + * M381 - Disable all solenoids. (Requires EXT_SOLENOID) + * M400 - Finish all moves. + * M401 - Lower Z probe. (Requires a probe) + * M402 - Raise Z probe. (Requires a probe) + * M404 - Display or set the Nominal Filament Width: "W". (Requires FILAMENT_WIDTH_SENSOR) + * M405 - Enable Filament Sensor flow control. "M405 D". (Requires FILAMENT_WIDTH_SENSOR) + * M406 - Disable Filament Sensor flow control. (Requires FILAMENT_WIDTH_SENSOR) + * M407 - Display measured filament diameter in millimeters. (Requires FILAMENT_WIDTH_SENSOR) + * M410 - Quickstop. Abort all planned moves. + * M420 - Enable/Disable Leveling (with current values) S1=enable S0=disable (Requires MESH_BED_LEVELING or ABL) + * M421 - Set a single Z coordinate in the Mesh Leveling grid. X Y Z (Requires MESH_BED_LEVELING) + * M428 - Set the home_offset based on the current_position. Nearest edge applies. + * M500 - Store parameters in EEPROM. (Requires EEPROM_SETTINGS) + * M501 - Restore parameters from EEPROM. (Requires EEPROM_SETTINGS) + * M502 - Revert to the default "factory settings". ** Does not write them to EEPROM! ** + * M503 - Print the current settings (in memory): "M503 S". S0 specifies compact output. + * M540 - Enable/disable SD card abort on endstop hit: "M540 S". (Requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) + * M600 - Pause for filament change: "M600 X Y Z E L". (Requires FILAMENT_CHANGE_FEATURE) + * M665 - Set delta configurations: "M665 L R S" (Requires DELTA) + * M666 - Set delta endstop adjustment. (Requires DELTA) + * M605 - Set dual x-carriage movement mode: "M605 S [X] [R]". (Requires DUAL_X_CARRIAGE) + * M851 - Set Z probe's Z offset in current units. (Negative = below the nozzle.) + * M907 - Set digital trimpot motor current using axis codes. (Requires a board with digital trimpots) + * M908 - Control digital trimpot directly. (Requires DAC_STEPPER_CURRENT or DIGIPOTSS_PIN) + * M909 - Print digipot/DAC current value. (Requires DAC_STEPPER_CURRENT) + * M910 - Commit digipot/DAC value to external EEPROM via I2C. (Requires DAC_STEPPER_CURRENT) + * M350 - Set microstepping mode. (Requires digital microstepping pins.) + * M351 - Toggle MS1 MS2 pins directly. (Requires digital microstepping pins.) + * + * ************ SCARA Specific - This can change to suit future G-code regulations + * M360 - SCARA calibration: Move to cal-position ThetaA (0 deg calibration) + * M361 - SCARA calibration: Move to cal-position ThetaB (90 deg calibration - steps per degree) + * M362 - SCARA calibration: Move to cal-position PsiA (0 deg calibration) + * M363 - SCARA calibration: Move to cal-position PsiB (90 deg calibration - steps per degree) + * M364 - SCARA calibration: Move to cal-position PSIC (90 deg to Theta calibration position) + * ************* SCARA End *************** + * + * ************ Custom codes - This can change to suit future G-code regulations + * M100 - Watch Free Memory (For Debugging). (Requires M100_FREE_MEMORY_WATCHER) + * M928 - Start SD logging: "M928 filename.gco". Stop with M29. (Requires SDSUPPORT) + * M999 - Restart after being stopped by error + * + * "T" Codes + * + * T0-T3 - Select an extruder (tool) by index: "T F" + * + */ + #include "Marlin.h" -#if ENABLED(AUTO_BED_LEVELING_FEATURE) - #include "vector_3.h" - #if ENABLED(AUTO_BED_LEVELING_GRID) - #include "qr_solve.h" - #endif -#endif // AUTO_BED_LEVELING_FEATURE - -#if ENABLED(MESH_BED_LEVELING) - #include "mesh_bed_leveling.h" -#endif - -#if ENABLED(BEZIER_CURVE_SUPPORT) - #include "planner_bezier.h" -#endif - #include "ultralcd.h" #include "planner.h" #include "stepper.h" @@ -63,6 +233,23 @@ #include "duration_t.h" #include "types.h" +#if HAS_ABL + #include "vector_3.h" + #if ENABLED(AUTO_BED_LEVELING_LINEAR) + #include "qr_solve.h" + #endif +#elif ENABLED(MESH_BED_LEVELING) + #include "mesh_bed_leveling.h" +#endif + +#if ENABLED(BEZIER_CURVE_SUPPORT) + #include "planner_bezier.h" +#endif + +#if HAS_BUZZER && DISABLED(LCD_USE_I2C_BUZZER) + #include "buzzer.h" +#endif + #if ENABLED(USE_WATCHDOG) #include "watchdog.h" #endif @@ -88,184 +275,9 @@ #include "twibus.h" #endif -/** - * Look here for descriptions of G-codes: - * - http://linuxcnc.org/handbook/gcode/g-code.html - * - http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes - * - * Help us document these G-codes online: - * - https://github.com/MarlinFirmware/Marlin/wiki/G-Code-in-Marlin - * - http://reprap.org/wiki/G-code - * - * ----------------- - * Implemented Codes - * ----------------- - * - * "G" Codes - * - * G0 -> G1 - * G1 - Coordinated Movement X Y Z E - * G2 - CW ARC - * G3 - CCW ARC - * G4 - Dwell S or P - * G5 - Cubic B-spline with XYZE destination and IJPQ offsets - * G10 - Retract filament according to settings of M207 - * G11 - Retract recover filament according to settings of M208 - * G12 - Clean tool - * G20 - Set input units to inches - * G21 - Set input units to millimeters - * G28 - Home one or more axes - * G29 - Detailed Z probe, probes the bed at 3 or more points. Will fail if you haven't homed yet. - * G30 - Single Z probe, probes bed at current XY location. - * G31 - Dock sled (Z_PROBE_SLED only) - * G32 - Undock sled (Z_PROBE_SLED only) - * G90 - Use Absolute Coordinates - * G91 - Use Relative Coordinates - * G92 - Set current position to coordinates given - * - * "M" Codes - * - * M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled) - * M1 - Same as M0 - * M17 - Enable/Power all stepper motors - * M18 - Disable all stepper motors; same as M84 - * M20 - List SD card - * M21 - Init SD card - * M22 - Release SD card - * M23 - Select SD file (M23 filename.g) - * M24 - Start/resume SD print - * M25 - Pause SD print - * M26 - Set SD position in bytes (M26 S12345) - * M27 - Report SD print status - * M28 - Start SD write (M28 filename.g) - * M29 - Stop SD write - * M30 - Delete file from SD (M30 filename.g) - * M31 - Output time since last M109 or SD card start to serial - * M32 - Select file and start SD print (Can be used _while_ printing from SD card files): - * syntax "M32 /path/filename#", or "M32 S !filename#" - * Call gcode file : "M32 P !filename#" and return to caller file after finishing (similar to #include). - * The '#' is necessary when calling from within sd files, as it stops buffer prereading - * M33 - Get the longname version of a path - * M42 - Change pin status via gcode Use M42 Px Sy to set pin x to value y, when omitting Px the onboard led will be used. - * M48 - Measure Z_Probe repeatability. M48 [P # of points] [X position] [Y position] [V_erboseness #] [E_ngage Probe] [L # of legs of travel] - * M75 - Start the print job timer - * M76 - Pause the print job timer - * M77 - Stop the print job timer - * M78 - Show statistical information about the print jobs - * M80 - Turn on Power Supply - * M81 - Turn off Power Supply - * M82 - Set E codes absolute (default) - * M83 - Set E codes relative while in Absolute Coordinates (G90) mode - * M84 - Disable steppers until next move, - * or use S to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout. - * M85 - Set inactivity shutdown timer with parameter S. To disable set zero (default) - * M92 - Set planner.axis_steps_per_mm - same syntax as G92 - * M104 - Set extruder target temp - * M105 - Read current temp - * M106 - Fan on - * M107 - Fan off - * M108 - Stop the waiting for heaters in M109, M190, M303. Does not affect the target temperature. - * M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating - * Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling - * IF AUTOTEMP is enabled, S B F. Exit autotemp by any M109 without F - * M110 - Set the current line number - * M111 - Set debug flags with S. See flag bits defined in enum.h. - * M112 - Emergency stop - * M113 - Get or set the timeout interval for Host Keepalive "busy" messages - * M114 - Output current position to serial port - * M115 - Capabilities string - * M117 - Display a message on the controller screen - * M119 - Output Endstop status to serial port - * M120 - Enable endstop detection - * M121 - Disable endstop detection - * M126 - Solenoid Air Valve Open (BariCUDA support by jmil) - * M127 - Solenoid Air Valve Closed (BariCUDA vent to atmospheric pressure by jmil) - * M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil) - * M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil) - * M140 - Set bed target temp - * M145 - Set the heatup state H B F for S (0=PLA, 1=ABS) - * M149 - Set temperature units - * M150 - Set BlinkM Color Output R: Red<0-255> U(!): Green<0-255> B: Blue<0-255> over i2c, G for green does not work. - * M163 - Set a single proportion for a mixing extruder. Requires MIXING_EXTRUDER. - * M164 - Save the mix as a virtual extruder. Requires MIXING_EXTRUDER and MIXING_VIRTUAL_TOOLS. - * M165 - Set the proportions for a mixing extruder. Use parameters ABCDHI to set the mixing factors. Requires MIXING_EXTRUDER. - * M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating - * Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling - * M200 - Set filament diameter, D, setting E axis units to cubic. (Use S0 to revert to linear units.) - * M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000) - * M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!! - * M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in units/sec - * M204 - Set default acceleration: P for Printing moves, R for Retract only (no X, Y, Z) moves and T for Travel (non printing) moves (ex. M204 P800 T3000 R9000) in units/sec^2 - * M205 - Set advanced settings. Current units apply: - S T minimum speeds - B - X, Z, E - * M206 - Set additional homing offset - * M207 - Set Retract Length: S, Feedrate: F, and Z lift: Z - * M208 - Set Recover (unretract) Additional (!) Length: S and Feedrate: F - * M209 - Turn Automatic Retract Detection on/off: S (For slicers that don't support G10/11). - Every normal extrude-only move will be classified as retract depending on the direction. - * M218 - Set a tool offset: T X Y - * M220 - Set Feedrate Percentage: S ("FR" on your LCD) - * M221 - Set Flow Percentage: S - * M226 - Wait until the specified pin reaches the state required: P S - * M240 - Trigger a camera to take a photograph - * M250 - Set LCD contrast C (value 0..63) - * M280 - Set servo position absolute. P: servo index, S: angle or microseconds - * M300 - Play beep sound S P - * M301 - Set PID parameters P I and D - * M302 - Allow cold extrudes, or set the minimum extrude S. - * M303 - PID relay autotune S sets the target temperature. (default target temperature = 150C) - * M304 - Set bed PID parameters P I and D - * M380 - Activate solenoid on active extruder - * M381 - Disable all solenoids - * M400 - Finish all moves - * M401 - Lower Z probe if present - * M402 - Raise Z probe if present - * M404 - Display or set the Nominal Filament Width: [ N ] - * M405 - Enable Filament Sensor extrusion control. Optional delay between sensor and extruder: D - * M406 - Disable Filament Sensor extrusion control - * M407 - Display measured filament diameter in millimeters - * M410 - Quickstop. Abort all the planned moves - * M420 - Enable/Disable Mesh Leveling (with current values) S1=enable S0=disable - * M421 - Set a single Z coordinate in the Mesh Leveling grid. X Y Z - * M428 - Set the home_offset logically based on the current_position - * M500 - Store parameters in EEPROM - * M501 - Read parameters from EEPROM (if you need reset them after you changed them temporarily). - * M502 - Revert to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. - * M503 - Print the current settings (from memory not from EEPROM). Use S0 to leave off headings. - * M540 - Use S[0|1] to enable or disable the stop SD card print on endstop hit (requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) - * M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal] - * M665 - Set delta configurations: L R S - * M666 - Set delta endstop adjustment - * M605 - Set dual x-carriage movement mode: S [ X R ] - * M851 - Set Z probe's Z offset in current units. (Negative values apply to probes that extend below the nozzle.) - * M907 - Set digital trimpot motor current using axis codes. - * M908 - Control digital trimpot directly. - * M909 - DAC_STEPPER_CURRENT: Print digipot/DAC current value - * M910 - DAC_STEPPER_CURRENT: Commit digipot/DAC value to external EEPROM via I2C - * M350 - Set microstepping mode. - * M351 - Toggle MS1 MS2 pins directly. - * - * ************ SCARA Specific - This can change to suit future G-code regulations - * M360 - SCARA calibration: Move to cal-position ThetaA (0 deg calibration) - * M361 - SCARA calibration: Move to cal-position ThetaB (90 deg calibration - steps per degree) - * M362 - SCARA calibration: Move to cal-position PsiA (0 deg calibration) - * M363 - SCARA calibration: Move to cal-position PsiB (90 deg calibration - steps per degree) - * M364 - SCARA calibration: Move to cal-position PSIC (90 deg to Theta calibration position) - * M365 - SCARA calibration: Scaling factor, X, Y, Z axis - * ************* SCARA End *************** - * - * ************ Custom codes - This can change to suit future G-code regulations - * M100 - Watch Free Memory (For Debugging Only) - * M928 - Start SD logging (M928 filename.g) - ended by M29 - * M999 - Restart after being stopped by error - * - * "T" Codes - * - * T0-T3 - Select a tool by index (usually an extruder) [ F ] - * - */ +#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE) + #include "endstop_interrupts.h" +#endif #if ENABLED(M100_FREE_MEMORY_WATCHER) void gcode_M100(); @@ -279,27 +291,82 @@ TWIBus i2c; #endif +#if ENABLED(G38_PROBE_TARGET) + bool G38_move = false, + G38_endstop_hit = false; +#endif + bool Running = true; uint8_t marlin_debug_flags = DEBUG_NONE; -float current_position[NUM_AXIS] = { 0.0 }; -static float destination[NUM_AXIS] = { 0.0 }; -bool axis_known_position[3] = { false }; -bool axis_homed[3] = { false }; +/** + * Cartesian Current Position + * Used to track the logical position as moves are queued. + * Used by 'line_to_current_position' to do a move after changing it. + * Used by 'SYNC_PLAN_POSITION_KINEMATIC' to update 'planner.position'. + */ +float current_position[XYZE] = { 0.0 }; +/** + * Cartesian Destination + * A temporary position, usually applied to 'current_position'. + * Set with 'gcode_get_destination' or 'set_destination_to_current'. + * 'line_to_destination' sets 'current_position' to 'destination'. + */ +static float destination[XYZE] = { 0.0 }; + +/** + * axis_homed + * Flags that each linear axis was homed. + * XYZ on cartesian, ABC on delta, ABZ on SCARA. + * + * axis_known_position + * Flags that the position is known in each linear axis. Set when homed. + * Cleared whenever a stepper powers off, potentially losing its position. + */ +bool axis_homed[XYZ] = { false }, axis_known_position[XYZ] = { false }; + +/** + * GCode line number handling. Hosts may opt to include line numbers when + * sending commands to Marlin, and lines will be checked for sequentiality. + * M110 S sets the current line number. + */ static long gcode_N, gcode_LastN, Stopped_gcode_LastN = 0; +/** + * GCode Command Queue + * A simple ring buffer of BUFSIZE command strings. + * + * Commands are copied into this buffer by the command injectors + * (immediate, serial, sd card) and they are processed sequentially by + * the main loop. The process_next_command function parses the next + * command and hands off execution to individual handler functions. + */ static char command_queue[BUFSIZE][MAX_CMD_SIZE]; -static char* current_command, *current_command_args; -static uint8_t cmd_queue_index_r = 0, - cmd_queue_index_w = 0, - commands_in_queue = 0; +static uint8_t cmd_queue_index_r = 0, // Ring buffer read position + cmd_queue_index_w = 0, // Ring buffer write position + commands_in_queue = 0; // Count of commands in the queue + +/** + * Current GCode Command + * When a GCode handler is running, these will be set + */ +static char *current_command, // The command currently being executed + *current_command_args, // The address where arguments begin + *seen_pointer; // Set by code_seen(), used by the code_value functions + +/** + * Next Injected Command pointer. NULL if no commands are being injected. + * Used by Marlin internally to ensure that commands initiated from within + * are enqueued ahead of any pending serial or sd card commands. + */ +static const char *injected_commands_P = NULL; #if ENABLED(INCH_MODE_SUPPORT) - float linear_unit_factor = 1.0; - float volumetric_unit_factor = 1.0; + float linear_unit_factor = 1.0, volumetric_unit_factor = 1.0; #endif + #if ENABLED(TEMPERATURE_UNITS_SUPPORT) TempUnit input_temp_units = TEMPUNIT_C; #endif @@ -308,33 +375,36 @@ static uint8_t cmd_queue_index_r = 0, * Feed rates are often configured with mm/m * but the planner and stepper like mm/s units. */ -const float homing_feedrate_mm_m[] = { +float constexpr homing_feedrate_mm_s[] = { #if ENABLED(DELTA) - HOMING_FEEDRATE_Z, HOMING_FEEDRATE_Z, + MMM_TO_MMS(HOMING_FEEDRATE_Z), MMM_TO_MMS(HOMING_FEEDRATE_Z), #else - HOMING_FEEDRATE_XY, HOMING_FEEDRATE_XY, + MMM_TO_MMS(HOMING_FEEDRATE_XY), MMM_TO_MMS(HOMING_FEEDRATE_XY), #endif - HOMING_FEEDRATE_Z, 0 + MMM_TO_MMS(HOMING_FEEDRATE_Z), 0 }; -static float feedrate_mm_m = 1500.0, saved_feedrate_mm_m; -int feedrate_percentage = 100, saved_feedrate_percentage; +static float feedrate_mm_s = MMM_TO_MMS(1500.0), saved_feedrate_mm_s; +int feedrate_percentage = 100, saved_feedrate_percentage, + flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); -bool axis_relative_modes[] = AXIS_RELATIVE_MODES; -int extruder_multiplier[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); -bool volumetric_enabled = false; -float filament_size[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_NOMINAL_FILAMENT_DIA); -float volumetric_multiplier[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0); +bool axis_relative_modes[] = AXIS_RELATIVE_MODES, + volumetric_enabled = false; +float filament_size[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_NOMINAL_FILAMENT_DIA), + volumetric_multiplier[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0); // The distance that XYZ has been offset by G92. Reset by G28. -float position_shift[3] = { 0 }; +float position_shift[XYZ] = { 0 }; // This offset is added to the configured home position. // Set by M206, M428, or menu item. Saved to EEPROM. -float home_offset[3] = { 0 }; +float home_offset[XYZ] = { 0 }; -// Software Endstops. Default to configured limits. -float sw_endstop_min[3] = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }; -float sw_endstop_max[3] = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS }; +// Software Endstops are based on the configured limits. +#if ENABLED(min_software_endstops) || ENABLED(max_software_endstops) + bool soft_endstops_enabled = true; +#endif +float soft_endstop_min[XYZ] = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }, + soft_endstop_max[XYZ] = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS }; #if FAN_COUNT > 0 int fanSpeeds[FAN_COUNT] = { 0 }; @@ -346,22 +416,21 @@ uint8_t active_extruder = 0; // Relative Mode. Enable with G91, disable with G90. static bool relative_mode = false; +// For M109 and M190, this flag may be cleared (by M108) to exit the wait loop volatile bool wait_for_heatup = true; +// For M0/M1, this flag may be cleared (by M108) to exit the wait-for-user loop +#if ENABLED(EMERGENCY_PARSER) || ENABLED(ULTIPANEL) + volatile bool wait_for_user = false; +#endif + const char errormagic[] PROGMEM = "Error:"; const char echomagic[] PROGMEM = "echo:"; const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'}; +// Number of characters read in the current line of serial input static int serial_count = 0; -// GCode parameter pointer used by code_seen(), code_value_float(), etc. -static char* seen_pointer; - -// Next Immediate GCode Command pointer. NULL if none. -const char* queued_commands_P = NULL; - -const int sensitive_pins[] = SENSITIVE_PINS; ///< Sensitive pin list for M42 - // Inactivity shutdown millis_t previous_cmd_ms = 0; static millis_t max_inactive_time = 0; @@ -377,7 +446,7 @@ static millis_t stepper_inactive_time = (DEFAULT_STEPPER_DEACTIVE_TIME) * 1000UL // Buzzer - I2C on the LCD or a BEEPER_PIN #if ENABLED(LCD_USE_I2C_BUZZER) #define BUZZ(d,f) lcd_buzz(d, f) -#elif HAS_BUZZER +#elif PIN_EXISTS(BEEPER) Buzzer buzzer; #define BUZZ(d,f) buzzer.tone(d, f) #else @@ -392,29 +461,38 @@ static uint8_t target_extruder; #define PLANNER_XY_FEEDRATE() (min(planner.max_feedrate_mm_s[X_AXIS], planner.max_feedrate_mm_s[Y_AXIS])) -#if ENABLED(AUTO_BED_LEVELING_FEATURE) - int xy_probe_feedrate_mm_m = XY_PROBE_SPEED; - bool bed_leveling_in_progress = false; - #define XY_PROBE_FEEDRATE_MM_M xy_probe_feedrate_mm_m +#if HAS_ABL + float xy_probe_feedrate_mm_s = MMM_TO_MMS(XY_PROBE_SPEED); + #define XY_PROBE_FEEDRATE_MM_S xy_probe_feedrate_mm_s #elif defined(XY_PROBE_SPEED) - #define XY_PROBE_FEEDRATE_MM_M XY_PROBE_SPEED + #define XY_PROBE_FEEDRATE_MM_S MMM_TO_MMS(XY_PROBE_SPEED) #else - #define XY_PROBE_FEEDRATE_MM_M MMS_TO_MMM(PLANNER_XY_FEEDRATE()) + #define XY_PROBE_FEEDRATE_MM_S PLANNER_XY_FEEDRATE() #endif -#if ENABLED(Z_DUAL_ENDSTOPS) && DISABLED(DELTA) +#if ENABLED(AUTO_BED_LEVELING_BILINEAR) + #if ENABLED(DELTA) + #define ADJUST_DELTA(V) \ + if (planner.abl_enabled) { \ + const float zadj = bilinear_z_offset(V); \ + delta[A_AXIS] += zadj; \ + delta[B_AXIS] += zadj; \ + delta[C_AXIS] += zadj; \ + } + #else + #define ADJUST_DELTA(V) if (planner.abl_enabled) { delta[Z_AXIS] += bilinear_z_offset(V); } + #endif +#elif IS_KINEMATIC + #define ADJUST_DELTA(V) NOOP +#endif + +#if ENABLED(Z_DUAL_ENDSTOPS) float z_endstop_adj = 0; #endif // Extruder offsets #if HOTENDS > 1 - float hotend_offset[][HOTENDS] = { - HOTEND_OFFSET_X, - HOTEND_OFFSET_Y - #ifdef HOTEND_OFFSET_Z - , HOTEND_OFFSET_Z - #endif - }; + float hotend_offset[XYZ][HOTENDS]; #endif #if HAS_Z_SERVO_ENDSTOP @@ -452,57 +530,73 @@ static uint8_t target_extruder; ; #endif +#if ENABLED(ULTIPANEL) && HAS_CASE_LIGHT + bool case_light_on = + #if ENABLED(CASE_LIGHT_DEFAULT_ON) + true + #else + false + #endif + ; +#endif + #if ENABLED(DELTA) - #define TOWER_1 X_AXIS - #define TOWER_2 Y_AXIS - #define TOWER_3 Z_AXIS - - float delta[3]; - float cartesian_position[3] = { 0 }; #define SIN_60 0.8660254037844386 #define COS_60 0.5 - float endstop_adj[3] = { 0 }; + + float delta[ABC], + endstop_adj[ABC] = { 0 }; + // these are the default values, can be overriden with M665 - float delta_radius = DELTA_RADIUS; - float delta_tower1_x = -SIN_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_1); // front left tower - float delta_tower1_y = -COS_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_1); - float delta_tower2_x = SIN_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_2); // front right tower - float delta_tower2_y = -COS_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_2); - float delta_tower3_x = 0; // back middle tower - float delta_tower3_y = (delta_radius + DELTA_RADIUS_TRIM_TOWER_3); - float delta_diagonal_rod = DELTA_DIAGONAL_ROD; - float delta_diagonal_rod_trim_tower_1 = DELTA_DIAGONAL_ROD_TRIM_TOWER_1; - float delta_diagonal_rod_trim_tower_2 = DELTA_DIAGONAL_ROD_TRIM_TOWER_2; - float delta_diagonal_rod_trim_tower_3 = DELTA_DIAGONAL_ROD_TRIM_TOWER_3; - float delta_diagonal_rod_2_tower_1 = sq(delta_diagonal_rod + delta_diagonal_rod_trim_tower_1); - float delta_diagonal_rod_2_tower_2 = sq(delta_diagonal_rod + delta_diagonal_rod_trim_tower_2); - float delta_diagonal_rod_2_tower_3 = sq(delta_diagonal_rod + delta_diagonal_rod_trim_tower_3); - float delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND; - float delta_clip_start_height = Z_MAX_POS; - #if ENABLED(AUTO_BED_LEVELING_FEATURE) - int delta_grid_spacing[2] = { 0, 0 }; - float bed_level[AUTO_BED_LEVELING_GRID_POINTS][AUTO_BED_LEVELING_GRID_POINTS]; - #endif + float delta_radius = DELTA_RADIUS, + delta_tower1_x = -SIN_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_1), // front left tower + delta_tower1_y = -COS_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_1), + delta_tower2_x = SIN_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_2), // front right tower + delta_tower2_y = -COS_60 * (delta_radius + DELTA_RADIUS_TRIM_TOWER_2), + delta_tower3_x = 0, // back middle tower + delta_tower3_y = (delta_radius + DELTA_RADIUS_TRIM_TOWER_3), + delta_diagonal_rod = DELTA_DIAGONAL_ROD, + delta_diagonal_rod_trim_tower_1 = DELTA_DIAGONAL_ROD_TRIM_TOWER_1, + delta_diagonal_rod_trim_tower_2 = DELTA_DIAGONAL_ROD_TRIM_TOWER_2, + delta_diagonal_rod_trim_tower_3 = DELTA_DIAGONAL_ROD_TRIM_TOWER_3, + delta_diagonal_rod_2_tower_1 = sq(delta_diagonal_rod + delta_diagonal_rod_trim_tower_1), + delta_diagonal_rod_2_tower_2 = sq(delta_diagonal_rod + delta_diagonal_rod_trim_tower_2), + delta_diagonal_rod_2_tower_3 = sq(delta_diagonal_rod + delta_diagonal_rod_trim_tower_3), + delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND, + delta_clip_start_height = Z_MAX_POS; + float delta_safe_distance_from_top(); + #else + static bool home_all_axis = true; + #endif -#if ENABLED(SCARA) - float delta_segments_per_second = SCARA_SEGMENTS_PER_SECOND; - float delta[3]; - float axis_scaling[3] = { 1, 1, 1 }; // Build size scaling, default to 1 +#if ENABLED(AUTO_BED_LEVELING_BILINEAR) + int bilinear_grid_spacing[2] = { 0 }, bilinear_start[2] = { 0 }; + float bed_level_grid[ABL_GRID_POINTS_X][ABL_GRID_POINTS_Y]; #endif +#if IS_SCARA + // Float constants for SCARA calculations + const float L1 = SCARA_LINKAGE_1, L2 = SCARA_LINKAGE_2, + L1_2 = sq(float(L1)), L1_2_2 = 2.0 * L1_2, + L2_2 = sq(float(L2)); + + float delta_segments_per_second = SCARA_SEGMENTS_PER_SECOND, + delta[ABC]; +#endif + +float cartes[XYZ] = { 0 }; + #if ENABLED(FILAMENT_WIDTH_SENSOR) - //Variables for Filament Sensor input - float filament_width_nominal = DEFAULT_NOMINAL_FILAMENT_DIA; //Set nominal filament width, can be changed with M404 bool filament_sensor = false; //M405 turns on filament_sensor control, M406 turns it off - float filament_width_meas = DEFAULT_MEASURED_FILAMENT_DIA; //Stores the measured filament diameter - int8_t measurement_delay[MAX_MEASUREMENT_DELAY + 1]; //ring buffer to delay measurement store extruder factor after subtracting 100 - int filwidth_delay_index1 = 0; //index into ring buffer - int filwidth_delay_index2 = -1; //index into ring buffer - set to -1 on startup to indicate ring buffer needs to be initialized + float filament_width_nominal = DEFAULT_NOMINAL_FILAMENT_DIA, // Nominal filament width. Change with M404 + filament_width_meas = DEFAULT_MEASURED_FILAMENT_DIA; // Measured filament diameter + int8_t measurement_delay[MAX_MEASUREMENT_DELAY + 1]; // Ring buffer to delayed measurement. Store extruder factor after subtracting 100 + int filwidth_delay_index[2] = { 0, -1 }; // Indexes into ring buffer int meas_delay_cm = MEASUREMENT_DELAY_CM; //distance delay setting #endif @@ -515,7 +609,7 @@ static uint8_t target_extruder; #endif #if ENABLED(MIXING_EXTRUDER) - float mixing_factor[MIXING_STEPPERS]; + float mixing_factor[MIXING_STEPPERS]; // Reciprocal of mix proportion. 0.0 = off, otherwise >= 1.0. #if MIXING_VIRTUAL_TOOLS > 1 float mixing_virtual_tool_mix[MIXING_VIRTUAL_TOOLS][MIXING_STEPPERS]; #endif @@ -551,6 +645,26 @@ static bool send_ok[BUFSIZE]; #define KEEPALIVE_STATE(n) ; #endif // HOST_KEEPALIVE_FEATURE +#define DEFINE_PGM_READ_ANY(type, reader) \ + static inline type pgm_read_any(const type *p) \ + { return pgm_read_##reader##_near(p); } + +DEFINE_PGM_READ_ANY(float, float) +DEFINE_PGM_READ_ANY(signed char, byte) + +#define XYZ_CONSTS_FROM_CONFIG(type, array, CONFIG) \ + static const PROGMEM type array##_P[XYZ] = \ + { X_##CONFIG, Y_##CONFIG, Z_##CONFIG }; \ + static inline type array(int axis) \ + { return pgm_read_any(&array##_P[axis]); } + +XYZ_CONSTS_FROM_CONFIG(float, base_min_pos, MIN_POS) +XYZ_CONSTS_FROM_CONFIG(float, base_max_pos, MAX_POS) +XYZ_CONSTS_FROM_CONFIG(float, base_home_pos, HOME_POS) +XYZ_CONSTS_FROM_CONFIG(float, max_length, MAX_LENGTH) +XYZ_CONSTS_FROM_CONFIG(float, home_bump_mm, HOME_BUMP_MM) +XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR) + /** * *************************************************************************** * ******************************** FUNCTIONS ******************************** @@ -562,7 +676,9 @@ void stop(); void get_available_commands(); void process_next_command(); void prepare_move_to_destination(); -void set_current_from_steppers_for_axis(AxisEnum axis); + +void get_cartesian_from_steppers(); +void set_current_from_steppers_for_axis(const AxisEnum axis); #if ENABLED(ARC_SUPPORT) void plan_arc(float target[NUM_AXIS], float* offset, uint8_t clockwise); @@ -572,6 +688,7 @@ void set_current_from_steppers_for_axis(AxisEnum axis); void plan_cubic_move(const float offset[4]); #endif +void serial_echopair_P(const char* s_P, const char *v) { serialprintPGM(s_P); SERIAL_ECHO(v); } void serial_echopair_P(const char* s_P, char v) { serialprintPGM(s_P); SERIAL_CHAR(v); } void serial_echopair_P(const char* s_P, int v) { serialprintPGM(s_P); SERIAL_ECHO(v); } void serial_echopair_P(const char* s_P, long v) { serialprintPGM(s_P); SERIAL_ECHO(v); } @@ -579,7 +696,7 @@ void serial_echopair_P(const char* s_P, float v) { serialprintPGM(s_P); void serial_echopair_P(const char* s_P, double v) { serialprintPGM(s_P); SERIAL_ECHO(v); } void serial_echopair_P(const char* s_P, unsigned long v) { serialprintPGM(s_P); SERIAL_ECHO(v); } -void tool_change(const uint8_t tmp_extruder, const float fr_mm_m=0.0, bool no_move=false); +void tool_change(const uint8_t tmp_extruder, const float fr_mm_s=0.0, bool no_move=false); static void report_current_position(); #if ENABLED(DEBUG_LEVELING_FEATURE) @@ -598,21 +715,21 @@ static void report_current_position(); print_xyz(prefix, suffix, xyz[X_AXIS], xyz[Y_AXIS], xyz[Z_AXIS]); } - #if ENABLED(AUTO_BED_LEVELING_FEATURE) + #if HAS_ABL void print_xyz(const char* prefix, const char* suffix, const vector_3 &xyz) { print_xyz(prefix, suffix, xyz.x, xyz.y, xyz.z); } #endif #define DEBUG_POS(SUFFIX,VAR) do { \ - print_xyz(PSTR(STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n"), VAR); } while(0) + print_xyz(PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n"), VAR); } while(0) #endif /** * sync_plan_position - * Set planner / stepper positions to the cartesian current_position. - * The stepper code translates these coordinates into step units. - * Allows translation between steps and millimeters for cartesian & core robots + * + * Set the planner/stepper positions directly from current_position with + * no kinematic translation. Used for homing axes and cartesian/core syncing. */ inline void sync_plan_position() { #if ENABLED(DEBUG_LEVELING_FEATURE) @@ -622,17 +739,20 @@ inline void sync_plan_position() { } inline void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); } -#if ENABLED(DELTA) || ENABLED(SCARA) - inline void sync_plan_position_delta() { +#if IS_KINEMATIC + + inline void sync_plan_position_kinematic() { #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) DEBUG_POS("sync_plan_position_delta", current_position); + if (DEBUGGING(LEVELING)) DEBUG_POS("sync_plan_position_kinematic", current_position); #endif - inverse_kinematics(current_position); - planner.set_position_mm(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS]); + planner.set_position_mm_kinematic(current_position); } - #define SYNC_PLAN_POSITION_KINEMATIC() sync_plan_position_delta() + #define SYNC_PLAN_POSITION_KINEMATIC() sync_plan_position_kinematic() + #else + #define SYNC_PLAN_POSITION_KINEMATIC() sync_plan_position() + #endif #if ENABLED(SDSUPPORT) @@ -664,32 +784,32 @@ extern "C" { * Inject the next "immediate" command, when possible. * Return true if any immediate commands remain to inject. */ -static bool drain_queued_commands_P() { - if (queued_commands_P != NULL) { +static bool drain_injected_commands_P() { + if (injected_commands_P != NULL) { size_t i = 0; char c, cmd[30]; - strncpy_P(cmd, queued_commands_P, sizeof(cmd) - 1); + strncpy_P(cmd, injected_commands_P, sizeof(cmd) - 1); cmd[sizeof(cmd) - 1] = '\0'; while ((c = cmd[i]) && c != '\n') i++; // find the end of this gcode command cmd[i] = '\0'; if (enqueue_and_echo_command(cmd)) { // success? if (c) // newline char? - queued_commands_P += i + 1; // advance to the next command + injected_commands_P += i + 1; // advance to the next command else - queued_commands_P = NULL; // nul char? no more commands + injected_commands_P = NULL; // nul char? no more commands } } - return (queued_commands_P != NULL); // return whether any more remain + return (injected_commands_P != NULL); // return whether any more remain } /** * Record one or many commands to run from program memory. * Aborts the current queue, if any. - * Note: drain_queued_commands_P() must be called repeatedly to drain the commands afterwards + * Note: drain_injected_commands_P() must be called repeatedly to drain the commands afterwards */ void enqueue_and_echo_commands_P(const char* pgcode) { - queued_commands_P = pgcode; - drain_queued_commands_P(); // first command executed asap (when possible) + injected_commands_P = pgcode; + drain_injected_commands_P(); // first command executed asap (when possible) } void clear_command_queue() { @@ -727,9 +847,9 @@ void enqueue_and_echo_command_now(const char* cmd) { bool enqueue_and_echo_command(const char* cmd, bool say_ok/*=false*/) { if (_enqueuecommand(cmd, say_ok)) { SERIAL_ECHO_START; - SERIAL_ECHOPGM(MSG_Enqueueing); - SERIAL_ECHO(cmd); - SERIAL_ECHOLNPGM("\""); + SERIAL_ECHOPAIR(MSG_Enqueueing, cmd); + SERIAL_CHAR('"'); + SERIAL_EOL; return true; } return false; @@ -745,7 +865,7 @@ void setup_killpin() { #if ENABLED(FILAMENT_RUNOUT_SENSOR) void setup_filrunoutpin() { - pinMode(FIL_RUNOUT_PIN, INPUT); + SET_INPUT(FIL_RUNOUT_PIN); #if ENABLED(ENDSTOPPULLUP_FIL_RUNOUT) WRITE(FIL_RUNOUT_PIN, HIGH); #endif @@ -761,13 +881,6 @@ void setup_homepin(void) { #endif } - -void setup_photpin() { - #if HAS_PHOTOGRAPH - OUT_WRITE(PHOTOGRAPH_PIN, LOW); - #endif -} - void setup_powerhold() { #if HAS_SUICIDE OUT_WRITE(SUICIDE_PIN, HIGH); @@ -817,10 +930,6 @@ void servo_init() { */ STOW_Z_SERVO(); #endif - - #if HAS_BED_PROBE - endstops.enable_z_probe(false); - #endif } /** @@ -828,216 +937,22 @@ void servo_init() { */ #if HAS_STEPPER_RESET void disableStepperDrivers() { - pinMode(STEPPER_RESET_PIN, OUTPUT); - digitalWrite(STEPPER_RESET_PIN, LOW); // drive it down to hold in reset motor driver chips + OUT_WRITE(STEPPER_RESET_PIN, LOW); // drive it down to hold in reset motor driver chips } - void enableStepperDrivers() { pinMode(STEPPER_RESET_PIN, INPUT); } // set to input, which allows it to be pulled high by pullups + void enableStepperDrivers() { SET_INPUT(STEPPER_RESET_PIN); } // set to input, which allows it to be pulled high by pullups #endif -/** - * Marlin entry-point: Set up before the program loop - * - Set up the kill pin, filament runout, power hold - * - Start the serial port - * - Print startup messages and diagnostics - * - Get EEPROM or default settings - * - Initialize managers for: - * • temperature - * • planner - * • watchdog - * • stepper - * • photo pin - * • servos - * • LCD controller - * • Digipot I2C - * • Z probe sled - * • status LEDs - */ -void setup() { +#if ENABLED(EXPERIMENTAL_I2CBUS) && I2C_SLAVE_ADDRESS > 0 - #ifdef DISABLE_JTAG - // Disable JTAG on AT90USB chips to free up pins for IO - MCUCR = 0x80; - MCUCR = 0x80; - #endif - - #if ENABLED(FILAMENT_RUNOUT_SENSOR) - setup_filrunoutpin(); - #endif - - setup_killpin(); - - setup_powerhold(); - - #if HAS_STEPPER_RESET - disableStepperDrivers(); - #endif - - MYSERIAL.begin(BAUDRATE); - SERIAL_PROTOCOLLNPGM("start"); - SERIAL_ECHO_START; - - // Check startup - does nothing if bootloader sets MCUSR to 0 - byte mcu = MCUSR; - if (mcu & 1) SERIAL_ECHOLNPGM(MSG_POWERUP); - if (mcu & 2) SERIAL_ECHOLNPGM(MSG_EXTERNAL_RESET); - if (mcu & 4) SERIAL_ECHOLNPGM(MSG_BROWNOUT_RESET); - if (mcu & 8) SERIAL_ECHOLNPGM(MSG_WATCHDOG_RESET); - if (mcu & 32) SERIAL_ECHOLNPGM(MSG_SOFTWARE_RESET); - MCUSR = 0; - - SERIAL_ECHOPGM(MSG_MARLIN); - SERIAL_ECHOLNPGM(" " SHORT_BUILD_VERSION); - - #ifdef STRING_DISTRIBUTION_DATE - #ifdef STRING_CONFIG_H_AUTHOR - SERIAL_ECHO_START; - SERIAL_ECHOPGM(MSG_CONFIGURATION_VER); - SERIAL_ECHOPGM(STRING_DISTRIBUTION_DATE); - SERIAL_ECHOPGM(MSG_AUTHOR); - SERIAL_ECHOLNPGM(STRING_CONFIG_H_AUTHOR); - SERIAL_ECHOPGM("Compiled: "); - SERIAL_ECHOLNPGM(__DATE__); - #endif // STRING_CONFIG_H_AUTHOR - #endif // STRING_DISTRIBUTION_DATE - - SERIAL_ECHO_START; - SERIAL_ECHOPGM(MSG_FREE_MEMORY); - SERIAL_ECHO(freeMemory()); - SERIAL_ECHOPGM(MSG_PLANNER_BUFFER_BYTES); - SERIAL_ECHOLN((int)sizeof(block_t)*BLOCK_BUFFER_SIZE); - - // Send "ok" after commands by default - for (int8_t i = 0; i < BUFSIZE; i++) send_ok[i] = true; - - // Load data from EEPROM if available (or use defaults) - // This also updates variables in the planner, elsewhere - Config_RetrieveSettings(); - - // Initialize current position based on home_offset - memcpy(current_position, home_offset, sizeof(home_offset)); - - // Vital to init stepper/planner equivalent for current_position - SYNC_PLAN_POSITION_KINEMATIC(); - - thermalManager.init(); // Initialize temperature loop - - #if ENABLED(USE_WATCHDOG) - watchdog_init(); - #endif - - stepper.init(); // Initialize stepper, this enables interrupts! - setup_photpin(); - servo_init(); - - #if HAS_CONTROLLERFAN - SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan - #endif - - #if HAS_STEPPER_RESET - enableStepperDrivers(); - #endif - - #if ENABLED(DIGIPOT_I2C) - digipot_i2c_init(); - #endif - - #if ENABLED(DAC_STEPPER_CURRENT) - dac_init(); - #endif - - #if ENABLED(Z_PROBE_SLED) && PIN_EXISTS(SLED) - pinMode(SLED_PIN, OUTPUT); - digitalWrite(SLED_PIN, LOW); // turn it off - #endif // Z_PROBE_SLED - - setup_homepin(); - - #ifdef STAT_LED_RED - pinMode(STAT_LED_RED, OUTPUT); - digitalWrite(STAT_LED_RED, LOW); // turn it off - #endif - - #ifdef STAT_LED_BLUE - pinMode(STAT_LED_BLUE, OUTPUT); - digitalWrite(STAT_LED_BLUE, LOW); // turn it off - #endif - - lcd_init(); - #if ENABLED(SHOW_BOOTSCREEN) - #if ENABLED(DOGLCD) - safe_delay(BOOTSCREEN_TIMEOUT); - #elif ENABLED(ULTRA_LCD) - bootscreen(); - lcd_init(); - #endif - #endif - - #if ENABLED(MIXING_EXTRUDER) && MIXING_VIRTUAL_TOOLS > 1 - // Initialize mixing to 100% color 1 - for (uint8_t i = 0; i < MIXING_STEPPERS; i++) - mixing_factor[i] = (i == 0) ? 1 : 0; - for (uint8_t t = 0; t < MIXING_VIRTUAL_TOOLS; t++) - for (uint8_t i = 0; i < MIXING_STEPPERS; i++) - mixing_virtual_tool_mix[t][i] = mixing_factor[i]; - #endif -} - -/** - * The main Marlin program loop - * - * - Save or log commands to SD - * - Process available commands (if not saving) - * - Call heater manager - * - Call inactivity manager - * - Call endstop manager - * - Call LCD update - */ -void loop() { - if (commands_in_queue < BUFSIZE) get_available_commands(); - - #if ENABLED(SDSUPPORT) - card.checkautostart(false); - #endif - - if (commands_in_queue) { - - #if ENABLED(SDSUPPORT) - - if (card.saving) { - char* command = command_queue[cmd_queue_index_r]; - if (strstr_P(command, PSTR("M29"))) { - // M29 closes the file - card.closefile(); - SERIAL_PROTOCOLLNPGM(MSG_FILE_SAVED); - ok_to_send(); - } - else { - // Write the string from the read buffer to SD - card.write_command(command); - if (card.logging) - process_next_command(); // The card is saving because it's logging - else - ok_to_send(); - } - } - else - process_next_command(); - - #else - - process_next_command(); - - #endif // SDSUPPORT - - // The queue may be reset by a command handler or by code invoked by idle() within a handler - if (commands_in_queue) { - --commands_in_queue; - cmd_queue_index_r = (cmd_queue_index_r + 1) % BUFSIZE; - } + void i2c_on_receive(int bytes) { // just echo all bytes received to serial + i2c.receive(bytes); } - endstops.report_state(); - idle(); -} + + void i2c_on_request() { // just send dummy data for now + i2c.reply("Hello World!\n"); + } + +#endif void gcode_line_error(const char* err, bool doFlush = true) { SERIAL_ERROR_START; @@ -1146,7 +1061,12 @@ inline void get_serial_commands() { #if DISABLED(EMERGENCY_PARSER) // If command was e-stop process now - if (strcmp(command, "M108") == 0) wait_for_heatup = false; + if (strcmp(command, "M108") == 0) { + wait_for_heatup = false; + #if ENABLED(ULTIPANEL) + wait_for_user = false; + #endif + } if (strcmp(command, "M112") == 0) kill(PSTR(MSG_KILLED)); if (strcmp(command, "M410") == 0) { quickstop_stepper(); } #endif @@ -1242,14 +1162,14 @@ inline void get_serial_commands() { /** * Add to the circular command queue the next command from: - * - The command-injection queue (queued_commands_P) + * - The command-injection queue (injected_commands_P) * - The active serial input (usually USB) * - The SD card file being actively printed */ void get_available_commands() { // if any immediate commands remain, don't get other commands yet - if (drain_queued_commands_P()) return; + if (drain_injected_commands_P()) return; get_serial_commands(); @@ -1290,7 +1210,7 @@ inline uint16_t code_value_ushort() { return (uint16_t)strtoul(seen_pointer + 1, inline uint8_t code_value_byte() { return (uint8_t)(constrain(strtol(seen_pointer + 1, NULL, 10), 0, 255)); } -inline bool code_value_bool() { return code_value_byte() > 0; } +inline bool code_value_bool() { return !code_has_value() || code_value_byte() > 0; } #if ENABLED(INCH_MODE_SUPPORT) inline void set_input_linear_units(LinearUnit units) { @@ -1307,7 +1227,7 @@ inline bool code_value_bool() { return code_value_byte() > 0; } } inline float axis_unit_factor(int axis) { - return (axis == E_AXIS && volumetric_enabled ? volumetric_unit_factor : linear_unit_factor); + return (axis >= E_AXIS && volumetric_enabled ? volumetric_unit_factor : linear_unit_factor); } inline float code_value_linear_units() { return code_value_float() * linear_unit_factor; } @@ -1373,8 +1293,7 @@ bool get_target_extruder_from_command(int code) { SERIAL_ECHO_START; SERIAL_CHAR('M'); SERIAL_ECHO(code); - SERIAL_ECHOPAIR(" " MSG_INVALID_EXTRUDER " ", code_value_byte()); - SERIAL_EOL; + SERIAL_ECHOLNPAIR(" " MSG_INVALID_EXTRUDER " ", code_value_byte()); return true; } target_extruder = code_value_byte(); @@ -1385,54 +1304,28 @@ bool get_target_extruder_from_command(int code) { return false; } -#define DEFINE_PGM_READ_ANY(type, reader) \ - static inline type pgm_read_any(const type *p) \ - { return pgm_read_##reader##_near(p); } - -DEFINE_PGM_READ_ANY(float, float); -DEFINE_PGM_READ_ANY(signed char, byte); - -#define XYZ_CONSTS_FROM_CONFIG(type, array, CONFIG) \ - static const PROGMEM type array##_P[3] = \ - { X_##CONFIG, Y_##CONFIG, Z_##CONFIG }; \ - static inline type array(int axis) \ - { return pgm_read_any(&array##_P[axis]); } - -XYZ_CONSTS_FROM_CONFIG(float, base_min_pos, MIN_POS); -XYZ_CONSTS_FROM_CONFIG(float, base_max_pos, MAX_POS); -XYZ_CONSTS_FROM_CONFIG(float, base_home_pos, HOME_POS); -XYZ_CONSTS_FROM_CONFIG(float, max_length, MAX_LENGTH); -XYZ_CONSTS_FROM_CONFIG(float, home_bump_mm, HOME_BUMP_MM); -XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR); - #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(DUAL_NOZZLE_DUPLICATION_MODE) bool extruder_duplication_enabled = false; // Used in Dual X mode 2 #endif #if ENABLED(DUAL_X_CARRIAGE) - #define DXC_FULL_CONTROL_MODE 0 - #define DXC_AUTO_PARK_MODE 1 - #define DXC_DUPLICATION_MODE 2 + static DualXMode dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; - static int dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; - - static float x_home_pos(int extruder) { + static float x_home_pos(const int extruder) { if (extruder == 0) return LOGICAL_X_POSITION(base_home_pos(X_AXIS)); else /** * In dual carriage mode the extruder offset provides an override of the - * second X-carriage offset when homed - otherwise X2_HOME_POS is used. - * This allow soft recalibration of the second extruder offset position + * second X-carriage position when homed - otherwise X2_HOME_POS is used. + * This allows soft recalibration of the second extruder home position * without firmware reflash (through the M218 command). */ - return (hotend_offset[X_AXIS][1] > 0) ? hotend_offset[X_AXIS][1] : X2_HOME_POS; + return LOGICAL_X_POSITION(hotend_offset[X_AXIS][1] > 0 ? hotend_offset[X_AXIS][1] : X2_HOME_POS); } - static int x_home_dir(int extruder) { - return (extruder == 0) ? X_HOME_DIR : X2_HOME_DIR; - } + static int x_home_dir(const int extruder) { return extruder ? X2_HOME_DIR : X_HOME_DIR; } static float inactive_extruder_x_pos = X2_MAX_POS; // used in mode 0 & 1 static bool active_extruder_parked = false; // used in mode 1 & 2 @@ -1441,7 +1334,7 @@ XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR); static float duplicate_extruder_x_offset = DEFAULT_DUPLICATION_X_OFFSET; // used in mode 2 static float duplicate_extruder_temp_offset = 0; // used in mode 2 -#endif //DUAL_X_CARRIAGE +#endif // DUAL_X_CARRIAGE /** * Software endstops can be used to monitor the open end of @@ -1452,45 +1345,51 @@ XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR); * the software endstop positions must be refreshed to remain * at the same positions relative to the machine. */ -static void update_software_endstops(AxisEnum axis) { +void update_software_endstops(AxisEnum axis) { float offs = LOGICAL_POSITION(0, axis); #if ENABLED(DUAL_X_CARRIAGE) + bool did_update = false; if (axis == X_AXIS) { + + // In Dual X mode hotend_offset[X] is T1's home position float dual_max_x = max(hotend_offset[X_AXIS][1], X2_MAX_POS); + if (active_extruder != 0) { - sw_endstop_min[X_AXIS] = X2_MIN_POS + offs; - sw_endstop_max[X_AXIS] = dual_max_x + offs; - return; + // T1 can move from X2_MIN_POS to X2_MAX_POS or X2 home position (whichever is larger) + soft_endstop_min[X_AXIS] = X2_MIN_POS + offs; + soft_endstop_max[X_AXIS] = dual_max_x + offs; } else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE) { - sw_endstop_min[X_AXIS] = base_min_pos(X_AXIS) + offs; - sw_endstop_max[X_AXIS] = min(base_max_pos(X_AXIS), dual_max_x - duplicate_extruder_x_offset) + offs; - return; + // In Duplication Mode, T0 can move as far left as X_MIN_POS + // but not so far to the right that T1 would move past the end + soft_endstop_min[X_AXIS] = base_min_pos(X_AXIS) + offs; + soft_endstop_max[X_AXIS] = min(base_max_pos(X_AXIS), dual_max_x - duplicate_extruder_x_offset) + offs; + } + else { + // In other modes, T0 can move from X_MIN_POS to X_MAX_POS + soft_endstop_min[axis] = base_min_pos(axis) + offs; + soft_endstop_max[axis] = base_max_pos(axis) + offs; } } - else + #else + soft_endstop_min[axis] = base_min_pos(axis) + offs; + soft_endstop_max[axis] = base_max_pos(axis) + offs; #endif - { - sw_endstop_min[axis] = base_min_pos(axis) + offs; - sw_endstop_max[axis] = base_max_pos(axis) + offs; - } #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR("For ", axis_codes[axis]); SERIAL_ECHOPAIR(" axis:\n home_offset = ", home_offset[axis]); SERIAL_ECHOPAIR("\n position_shift = ", position_shift[axis]); - SERIAL_ECHOPAIR("\n sw_endstop_min = ", sw_endstop_min[axis]); - SERIAL_ECHOPAIR("\n sw_endstop_max = ", sw_endstop_max[axis]); - SERIAL_EOL; + SERIAL_ECHOPAIR("\n soft_endstop_min = ", soft_endstop_min[axis]); + SERIAL_ECHOLNPAIR("\n soft_endstop_max = ", soft_endstop_max[axis]); } #endif #if ENABLED(DELTA) - if (axis == Z_AXIS) { - delta_clip_start_height = sw_endstop_max[axis] - delta_safe_distance_from_top(); - } + if (axis == Z_AXIS) + delta_clip_start_height = soft_endstop_max[axis] - delta_safe_distance_from_top(); #endif } @@ -1509,87 +1408,115 @@ static void set_home_offset(AxisEnum axis, float v) { update_software_endstops(axis); } +/** + * Set an axis' current position to its home position (after homing). + * + * For Core and Cartesian robots this applies one-to-one when an + * individual axis has been homed. + * + * DELTA should wait until all homing is done before setting the XYZ + * current_position to home, because homing is a single operation. + * In the case where the axis positions are already known and previously + * homed, DELTA could home to X or Y individually by moving either one + * to the center. However, homing Z always homes XY and Z. + * + * SCARA should wait until all XY homing is done before setting the XY + * current_position to home, because neither X nor Y is at home until + * both are at home. Z can however be homed individually. + * + * Callers must sync the planner position after calling this! + */ static void set_axis_is_at_home(AxisEnum axis) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR(">>> set_axis_is_at_home(", axis); - SERIAL_ECHOLNPGM(")"); + SERIAL_ECHOPAIR(">>> set_axis_is_at_home(", axis_codes[axis]); + SERIAL_CHAR(')'); + SERIAL_EOL; } #endif + axis_known_position[axis] = axis_homed[axis] = true; + position_shift[axis] = 0; + update_software_endstops(axis); #if ENABLED(DUAL_X_CARRIAGE) - if (axis == X_AXIS && (active_extruder != 0 || dual_x_carriage_mode == DXC_DUPLICATION_MODE)) { - if (active_extruder != 0) - current_position[X_AXIS] = x_home_pos(active_extruder); - else - current_position[X_AXIS] = LOGICAL_X_POSITION(base_home_pos(X_AXIS)); - update_software_endstops(X_AXIS); + if (axis == X_AXIS && (active_extruder == 1 || dual_x_carriage_mode == DXC_DUPLICATION_MODE)) { + current_position[X_AXIS] = x_home_pos(active_extruder); return; } #endif - #if ENABLED(SCARA) + #if ENABLED(MORGAN_SCARA) + /** + * Morgan SCARA homes XY at the same time + */ if (axis == X_AXIS || axis == Y_AXIS) { - float homeposition[3]; - LOOP_XYZ(i) homeposition[i] = LOGICAL_POSITION(base_home_pos(i), i); + float homeposition[XYZ]; + LOOP_XYZ(i) homeposition[i] = LOGICAL_POSITION(base_home_pos((AxisEnum)i), i); - // SERIAL_ECHOPGM("homeposition[x]= "); SERIAL_ECHO(homeposition[0]); - // SERIAL_ECHOPGM("homeposition[y]= "); SERIAL_ECHOLN(homeposition[1]); + // SERIAL_ECHOPAIR("homeposition X:", homeposition[X_AXIS]); + // SERIAL_ECHOLNPAIR(" Y:", homeposition[Y_AXIS]); /** - * Works out real Homeposition angles using inverse kinematics, - * and calculates homing offset using forward kinematics + * Get Home position SCARA arm angles using inverse kinematics, + * and calculate homing offset using forward kinematics */ inverse_kinematics(homeposition); - forward_kinematics_SCARA(delta); + forward_kinematics_SCARA(delta[A_AXIS], delta[B_AXIS]); - // SERIAL_ECHOPAIR("Delta X=", delta[X_AXIS]); - // SERIAL_ECHOPGM(" Delta Y="); SERIAL_ECHOLN(delta[Y_AXIS]); + // SERIAL_ECHOPAIR("Cartesian X:", cartes[X_AXIS]); + // SERIAL_ECHOLNPAIR(" Y:", cartes[Y_AXIS]); - current_position[axis] = LOGICAL_POSITION(delta[axis], axis); + current_position[axis] = LOGICAL_POSITION(cartes[axis], axis); /** * SCARA home positions are based on configuration since the actual * limits are determined by the inverse kinematic transform. */ - sw_endstop_min[axis] = base_min_pos(axis); // + (delta[axis] - base_home_pos(axis)); - sw_endstop_max[axis] = base_max_pos(axis); // + (delta[axis] - base_home_pos(axis)); + soft_endstop_min[axis] = base_min_pos(axis); // + (cartes[axis] - base_home_pos(axis)); + soft_endstop_max[axis] = base_max_pos(axis); // + (cartes[axis] - base_home_pos(axis)); } else #endif { current_position[axis] = LOGICAL_POSITION(base_home_pos(axis), axis); - update_software_endstops(axis); + } + + /** + * Z Probe Z Homing? Account for the probe's Z offset. + */ + #if HAS_BED_PROBE && Z_HOME_DIR < 0 + if (axis == Z_AXIS) { + #if HOMING_Z_WITH_PROBE - #if HAS_BED_PROBE && Z_HOME_DIR < 0 && DISABLED(Z_MIN_PROBE_ENDSTOP) - if (axis == Z_AXIS) { current_position[Z_AXIS] -= zprobe_zoffset; + #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR("> zprobe_zoffset = ", zprobe_zoffset); - SERIAL_EOL; + SERIAL_ECHOLNPGM("*** Z HOMED WITH PROBE (Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) ***"); + SERIAL_ECHOLNPAIR("> zprobe_zoffset = ", zprobe_zoffset); } #endif - } - #endif - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR("> home_offset[", axis_codes[axis]); - SERIAL_ECHOPAIR("] = ", home_offset[axis]); - SERIAL_EOL; - DEBUG_POS("", current_position); - } - #endif - } + #elif ENABLED(DEBUG_LEVELING_FEATURE) + + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("*** Z HOMED TO ENDSTOP (Z_MIN_PROBE_ENDSTOP) ***"); + + #endif + } + #endif + #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR("<<< set_axis_is_at_home(", axis); - SERIAL_ECHOLNPGM(")"); + SERIAL_ECHOPAIR("> home_offset[", axis_codes[axis]); + SERIAL_ECHOLNPAIR("] = ", home_offset[axis]); + DEBUG_POS("", current_position); + SERIAL_ECHOPAIR("<<< set_axis_is_at_home(", axis_codes[axis]); + SERIAL_CHAR(')'); + SERIAL_EOL; } #endif } @@ -1598,70 +1525,64 @@ static void set_axis_is_at_home(AxisEnum axis) { * Some planner shorthand inline functions */ inline float get_homing_bump_feedrate(AxisEnum axis) { - const int homing_bump_divisor[] = HOMING_BUMP_DIVISOR; + int constexpr homing_bump_divisor[] = HOMING_BUMP_DIVISOR; int hbd = homing_bump_divisor[axis]; if (hbd < 1) { hbd = 10; SERIAL_ECHO_START; SERIAL_ECHOLNPGM("Warning: Homing Bump Divisor < 1"); } - return homing_feedrate_mm_m[axis] / hbd; + return homing_feedrate_mm_s[axis] / hbd; } + // // line_to_current_position // Move the planner to the current position from wherever it last moved // (or from wherever it has been told it is located). // inline void line_to_current_position() { - planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], MMM_TO_MMS(feedrate_mm_m), active_extruder); -} - -inline void line_to_z(float zPosition) { - planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], MMM_TO_MMS(feedrate_mm_m), active_extruder); -} - -inline void line_to_axis_pos(AxisEnum axis, float where, float fr_mm_m = 0.0) { - float old_feedrate_mm_m = feedrate_mm_m; - current_position[axis] = where; - feedrate_mm_m = (fr_mm_m != 0.0) ? fr_mm_m : homing_feedrate_mm_m[axis]; - planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], MMM_TO_MMS(feedrate_mm_m), active_extruder); - stepper.synchronize(); - feedrate_mm_m = old_feedrate_mm_m; + planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate_mm_s, active_extruder); } // // line_to_destination // Move the planner, not necessarily synced with current_position // -inline void line_to_destination(float fr_mm_m) { - planner.buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], MMM_TO_MMS(fr_mm_m), active_extruder); +inline void line_to_destination(float fr_mm_s) { + planner.buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], fr_mm_s, active_extruder); } -inline void line_to_destination() { line_to_destination(feedrate_mm_m); } +inline void line_to_destination() { line_to_destination(feedrate_mm_s); } inline void set_current_to_destination() { memcpy(current_position, destination, sizeof(current_position)); } inline void set_destination_to_current() { memcpy(destination, current_position, sizeof(destination)); } -#if ENABLED(DELTA) +#if IS_KINEMATIC /** * Calculate delta, start a line, and set current_position to destination */ - void prepare_move_to_destination_raw() { + void prepare_uninterpolated_move_to_destination(const float fr_mm_s=0.0) { #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) DEBUG_POS("prepare_move_to_destination_raw", destination); + if (DEBUGGING(LEVELING)) DEBUG_POS("prepare_uninterpolated_move_to_destination", destination); #endif + + if ( current_position[X_AXIS] == destination[X_AXIS] + && current_position[Y_AXIS] == destination[Y_AXIS] + && current_position[Z_AXIS] == destination[Z_AXIS] + && current_position[E_AXIS] == destination[E_AXIS] + ) return; + refresh_cmd_timeout(); - inverse_kinematics(destination); - planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], destination[E_AXIS], MMM_TO_MMS_SCALED(feedrate_mm_m), active_extruder); + planner.buffer_line_kinematic(destination, MMS_SCALED(fr_mm_s ? fr_mm_s : feedrate_mm_s), active_extruder); set_current_to_destination(); } -#endif +#endif // IS_KINEMATIC /** * Plan a move to (X, Y, Z) and set the current_position * The final current_position may not be the one that was requested */ -void do_blocking_move_to(float x, float y, float z, float fr_mm_m /*=0.0*/) { - float old_feedrate_mm_m = feedrate_mm_m; +void do_blocking_move_to(const float &x, const float &y, const float &z, const float &fr_mm_s /*=0.0*/) { + float old_feedrate_mm_s = feedrate_mm_s; #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) print_xyz(PSTR(">>> do_blocking_move_to"), NULL, x, y, z); @@ -1669,7 +1590,7 @@ void do_blocking_move_to(float x, float y, float z, float fr_mm_m /*=0.0*/) { #if ENABLED(DELTA) - feedrate_mm_m = (fr_mm_m != 0.0) ? fr_mm_m : XY_PROBE_FEEDRATE_MM_M; + feedrate_mm_s = fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S; set_destination_to_current(); // sync destination at the start @@ -1683,7 +1604,7 @@ void do_blocking_move_to(float x, float y, float z, float fr_mm_m /*=0.0*/) { destination[X_AXIS] = x; // move directly (uninterpolated) destination[Y_AXIS] = y; destination[Z_AXIS] = z; - prepare_move_to_destination_raw(); // set_current_to_destination + prepare_uninterpolated_move_to_destination(); // set_current_to_destination #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("danger zone move", current_position); #endif @@ -1691,7 +1612,7 @@ void do_blocking_move_to(float x, float y, float z, float fr_mm_m /*=0.0*/) { } else { destination[Z_AXIS] = delta_clip_start_height; - prepare_move_to_destination_raw(); // set_current_to_destination + prepare_uninterpolated_move_to_destination(); // set_current_to_destination #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("zone border move", current_position); #endif @@ -1700,7 +1621,7 @@ void do_blocking_move_to(float x, float y, float z, float fr_mm_m /*=0.0*/) { if (z > current_position[Z_AXIS]) { // raising? destination[Z_AXIS] = z; - prepare_move_to_destination_raw(); // set_current_to_destination + prepare_uninterpolated_move_to_destination(); // set_current_to_destination #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("z raise move", current_position); #endif @@ -1715,33 +1636,49 @@ void do_blocking_move_to(float x, float y, float z, float fr_mm_m /*=0.0*/) { if (z < current_position[Z_AXIS]) { // lowering? destination[Z_AXIS] = z; - prepare_move_to_destination_raw(); // set_current_to_destination + prepare_uninterpolated_move_to_destination(); // set_current_to_destination #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position); #endif } - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< do_blocking_move_to"); - #endif + #elif IS_SCARA + + set_destination_to_current(); + + // If Z needs to raise, do it before moving XY + if (destination[Z_AXIS] < z) { + destination[Z_AXIS] = z; + prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : homing_feedrate_mm_s[Z_AXIS]); + } + + destination[X_AXIS] = x; + destination[Y_AXIS] = y; + prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S); + + // If Z needs to lower, do it after moving XY + if (destination[Z_AXIS] > z) { + destination[Z_AXIS] = z; + prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : homing_feedrate_mm_s[Z_AXIS]); + } #else // If Z needs to raise, do it before moving XY if (current_position[Z_AXIS] < z) { - feedrate_mm_m = (fr_mm_m != 0.0) ? fr_mm_m : homing_feedrate_mm_m[Z_AXIS]; + feedrate_mm_s = fr_mm_s ? fr_mm_s : homing_feedrate_mm_s[Z_AXIS]; current_position[Z_AXIS] = z; line_to_current_position(); } - feedrate_mm_m = (fr_mm_m != 0.0) ? fr_mm_m : XY_PROBE_FEEDRATE_MM_M; + feedrate_mm_s = fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S; current_position[X_AXIS] = x; current_position[Y_AXIS] = y; line_to_current_position(); // If Z needs to lower, do it after moving XY if (current_position[Z_AXIS] > z) { - feedrate_mm_m = (fr_mm_m != 0.0) ? fr_mm_m : homing_feedrate_mm_m[Z_AXIS]; + feedrate_mm_s = fr_mm_s ? fr_mm_s : homing_feedrate_mm_s[Z_AXIS]; current_position[Z_AXIS] = z; line_to_current_position(); } @@ -1750,16 +1687,20 @@ void do_blocking_move_to(float x, float y, float z, float fr_mm_m /*=0.0*/) { stepper.synchronize(); - feedrate_mm_m = old_feedrate_mm_m; + feedrate_mm_s = old_feedrate_mm_s; + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< do_blocking_move_to"); + #endif } -void do_blocking_move_to_x(float x, float fr_mm_m/*=0.0*/) { - do_blocking_move_to(x, current_position[Y_AXIS], current_position[Z_AXIS], fr_mm_m); +void do_blocking_move_to_x(const float &x, const float &fr_mm_s/*=0.0*/) { + do_blocking_move_to(x, current_position[Y_AXIS], current_position[Z_AXIS], fr_mm_s); } -void do_blocking_move_to_z(float z, float fr_mm_m/*=0.0*/) { - do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], z, fr_mm_m); +void do_blocking_move_to_z(const float &z, const float &fr_mm_s/*=0.0*/) { + do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], z, fr_mm_s); } -void do_blocking_move_to_xy(float x, float y, float fr_mm_m/*=0.0*/) { - do_blocking_move_to(x, y, current_position[Z_AXIS], fr_mm_m); +void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s/*=0.0*/) { + do_blocking_move_to(x, y, current_position[Z_AXIS], fr_mm_s); } // @@ -1775,7 +1716,7 @@ static void setup_for_endstop_or_probe_move() { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("setup_for_endstop_or_probe_move", current_position); #endif - saved_feedrate_mm_m = feedrate_mm_m; + saved_feedrate_mm_s = feedrate_mm_s; saved_feedrate_percentage = feedrate_percentage; feedrate_percentage = 100; refresh_cmd_timeout(); @@ -1785,7 +1726,7 @@ static void clean_up_after_endstop_or_probe_move() { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("clean_up_after_endstop_or_probe_move", current_position); #endif - feedrate_mm_m = saved_feedrate_mm_m; + feedrate_mm_s = saved_feedrate_mm_s; feedrate_percentage = saved_feedrate_percentage; refresh_cmd_timeout(); } @@ -1798,17 +1739,21 @@ static void clean_up_after_endstop_or_probe_move() { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR("do_probe_raise(", z_raise); - SERIAL_ECHOLNPGM(")"); + SERIAL_CHAR(')'); + SERIAL_EOL; } #endif + float z_dest = LOGICAL_Z_POSITION(z_raise); + if (zprobe_zoffset < 0) z_dest -= zprobe_zoffset; + if (z_dest > current_position[Z_AXIS]) do_blocking_move_to_z(z_dest); } #endif //HAS_BED_PROBE -#if ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) || ENABLED(Z_SAFE_HOMING) || HAS_PROBING_PROCEDURE || HOTENDS > 1 || ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE) +#if ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) || HAS_PROBING_PROCEDURE || HOTENDS > 1 || ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE) static bool axis_unhomed_error(const bool x, const bool y, const bool z) { const bool xx = x && !axis_homed[X_AXIS], yy = y && !axis_homed[Y_AXIS], @@ -1852,7 +1797,8 @@ static void clean_up_after_endstop_or_probe_move() { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR("dock_sled(", stow); - SERIAL_ECHOLNPGM(")"); + SERIAL_CHAR(')'); + SERIAL_EOL; } #endif @@ -1864,8 +1810,8 @@ static void clean_up_after_endstop_or_probe_move() { #endif } -#endif // Z_PROBE_SLED -#if ENABLED(Z_PROBE_ALLEN_KEY) +#elif ENABLED(Z_PROBE_ALLEN_KEY) + void run_deploy_moves_script() { #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_Z) #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_X @@ -1880,7 +1826,7 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_1_X, Z_PROBE_ALLEN_KEY_DEPLOY_1_Y, Z_PROBE_ALLEN_KEY_DEPLOY_1_Z, Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE); + do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_1_X, Z_PROBE_ALLEN_KEY_DEPLOY_1_Y, Z_PROBE_ALLEN_KEY_DEPLOY_1_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_Z) #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_X @@ -1895,7 +1841,7 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_2_X, Z_PROBE_ALLEN_KEY_DEPLOY_2_Y, Z_PROBE_ALLEN_KEY_DEPLOY_2_Z, Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE); + do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_2_X, Z_PROBE_ALLEN_KEY_DEPLOY_2_Y, Z_PROBE_ALLEN_KEY_DEPLOY_2_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_Z) #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_X @@ -1910,7 +1856,7 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_3_X, Z_PROBE_ALLEN_KEY_DEPLOY_3_Y, Z_PROBE_ALLEN_KEY_DEPLOY_3_Z, Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE); + do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_3_X, Z_PROBE_ALLEN_KEY_DEPLOY_3_Y, Z_PROBE_ALLEN_KEY_DEPLOY_3_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_Z) #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_X @@ -1925,7 +1871,7 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_4_X, Z_PROBE_ALLEN_KEY_DEPLOY_4_Y, Z_PROBE_ALLEN_KEY_DEPLOY_4_Z, Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE); + do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_4_X, Z_PROBE_ALLEN_KEY_DEPLOY_4_Y, Z_PROBE_ALLEN_KEY_DEPLOY_4_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_Z) #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_X @@ -1940,9 +1886,10 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_5_X, Z_PROBE_ALLEN_KEY_DEPLOY_5_Y, Z_PROBE_ALLEN_KEY_DEPLOY_5_Z, Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE); + do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_5_X, Z_PROBE_ALLEN_KEY_DEPLOY_5_Y, Z_PROBE_ALLEN_KEY_DEPLOY_5_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE)); #endif } + void run_stow_moves_script() { #if defined(Z_PROBE_ALLEN_KEY_STOW_1_X) || defined(Z_PROBE_ALLEN_KEY_STOW_1_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_1_Z) #ifndef Z_PROBE_ALLEN_KEY_STOW_1_X @@ -1957,7 +1904,7 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_1_X, Z_PROBE_ALLEN_KEY_STOW_1_Y, Z_PROBE_ALLEN_KEY_STOW_1_Z, Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE); + do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_1_X, Z_PROBE_ALLEN_KEY_STOW_1_Y, Z_PROBE_ALLEN_KEY_STOW_1_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_STOW_2_X) || defined(Z_PROBE_ALLEN_KEY_STOW_2_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_2_Z) #ifndef Z_PROBE_ALLEN_KEY_STOW_2_X @@ -1972,7 +1919,7 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_2_X, Z_PROBE_ALLEN_KEY_STOW_2_Y, Z_PROBE_ALLEN_KEY_STOW_2_Z, Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE); + do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_2_X, Z_PROBE_ALLEN_KEY_STOW_2_Y, Z_PROBE_ALLEN_KEY_STOW_2_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_STOW_3_X) || defined(Z_PROBE_ALLEN_KEY_STOW_3_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_3_Z) #ifndef Z_PROBE_ALLEN_KEY_STOW_3_X @@ -1987,7 +1934,7 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_3_X, Z_PROBE_ALLEN_KEY_STOW_3_Y, Z_PROBE_ALLEN_KEY_STOW_3_Z, Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE); + do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_3_X, Z_PROBE_ALLEN_KEY_STOW_3_Y, Z_PROBE_ALLEN_KEY_STOW_3_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_STOW_4_X) || defined(Z_PROBE_ALLEN_KEY_STOW_4_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_4_Z) #ifndef Z_PROBE_ALLEN_KEY_STOW_4_X @@ -2002,7 +1949,7 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_4_X, Z_PROBE_ALLEN_KEY_STOW_4_Y, Z_PROBE_ALLEN_KEY_STOW_4_Z, Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE); + do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_4_X, Z_PROBE_ALLEN_KEY_STOW_4_Y, Z_PROBE_ALLEN_KEY_STOW_4_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_STOW_5_X) || defined(Z_PROBE_ALLEN_KEY_STOW_5_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_5_Z) #ifndef Z_PROBE_ALLEN_KEY_STOW_5_X @@ -2017,9 +1964,10 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_5_X, Z_PROBE_ALLEN_KEY_STOW_5_Y, Z_PROBE_ALLEN_KEY_STOW_5_Z, Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE); + do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_5_X, Z_PROBE_ALLEN_KEY_STOW_5_Y, Z_PROBE_ALLEN_KEY_STOW_5_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE)); #endif } + #endif #if HAS_BED_PROBE @@ -2033,8 +1981,21 @@ static void clean_up_after_endstop_or_probe_move() { #endif #endif - #define DEPLOY_PROBE() set_probe_deployed( true ) - #define STOW_PROBE() set_probe_deployed( false ) + #define DEPLOY_PROBE() set_probe_deployed(true) + #define STOW_PROBE() set_probe_deployed(false) + + #if ENABLED(BLTOUCH) + FORCE_INLINE void set_bltouch_deployed(const bool &deploy) { + servo[Z_ENDSTOP_SERVO_NR].move(deploy ? BLTOUCH_DEPLOY : BLTOUCH_STOW); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) { + SERIAL_ECHOPAIR("set_bltouch_deployed(", deploy); + SERIAL_CHAR(')'); + SERIAL_EOL; + } + #endif + } + #endif // returns false for ok and true for failure static bool set_probe_deployed(bool deploy) { @@ -2042,48 +2003,58 @@ static void clean_up_after_endstop_or_probe_move() { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { DEBUG_POS("set_probe_deployed", current_position); - SERIAL_ECHOPAIR("deploy: ", deploy); - SERIAL_EOL; + SERIAL_ECHOLNPAIR("deploy: ", deploy); } #endif if (endstops.z_probe_enabled == deploy) return false; // Make room for probe - do_probe_raise(_Z_PROBE_DEPLOY_HEIGHT); + do_probe_raise(_Z_CLEARANCE_DEPLOY_PROBE); - #if ENABLED(Z_PROBE_SLED) + // When deploying make sure BLTOUCH is not already triggered + #if ENABLED(BLTOUCH) + if (deploy && TEST_BLTOUCH()) { stop(); return true; } + #elif ENABLED(Z_PROBE_SLED) if (axis_unhomed_error(true, false, false)) { stop(); return true; } #elif ENABLED(Z_PROBE_ALLEN_KEY) if (axis_unhomed_error(true, true, true )) { stop(); return true; } #endif - float oldXpos = current_position[X_AXIS]; // save x position - float oldYpos = current_position[Y_AXIS]; // save y position + float oldXpos = current_position[X_AXIS], + oldYpos = current_position[Y_AXIS]; #ifdef _TRIGGERED_WHEN_STOWED_TEST + // If endstop is already false, the Z probe is deployed - if (_TRIGGERED_WHEN_STOWED_TEST == deploy) { // closed after the probe specific actions. - // Would a goto be less ugly? - //while (!_TRIGGERED_WHEN_STOWED_TEST) { idle(); // would offer the opportunity - // for a triggered when stowed manual probe. + if (_TRIGGERED_WHEN_STOWED_TEST == deploy) { // closed after the probe specific actions. + // Would a goto be less ugly? + //while (!_TRIGGERED_WHEN_STOWED_TEST) idle(); // would offer the opportunity + // for a triggered when stowed manual probe. + + if (!deploy) endstops.enable_z_probe(false); // Switch off triggered when stowed probes early + // otherwise an Allen-Key probe can't be stowed. #endif - #if ENABLED(Z_PROBE_SLED) - dock_sled(!deploy); - #elif HAS_Z_SERVO_ENDSTOP - servo[Z_ENDSTOP_SERVO_NR].move(z_servo_angle[((deploy) ? 0 : 1)]); - #elif ENABLED(Z_PROBE_ALLEN_KEY) - if (!deploy) run_stow_moves_script(); - else run_deploy_moves_script(); - #else - // Nothing to be done. Just enable_z_probe below... - #endif + #if ENABLED(Z_PROBE_SLED) + + dock_sled(!deploy); + + #elif HAS_Z_SERVO_ENDSTOP && DISABLED(BLTOUCH) + + servo[Z_ENDSTOP_SERVO_NR].move(z_servo_angle[deploy ? 0 : 1]); + + #elif ENABLED(Z_PROBE_ALLEN_KEY) + + deploy ? run_deploy_moves_script() : run_stow_moves_script(); + + #endif #ifdef _TRIGGERED_WHEN_STOWED_TEST - }; // opened before the probe specific actions + } // _TRIGGERED_WHEN_STOWED_TEST == deploy + + if (_TRIGGERED_WHEN_STOWED_TEST == deploy) { // State hasn't changed? - if (_TRIGGERED_WHEN_STOWED_TEST == deploy) { if (IsRunning()) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM("Z-Probe failed"); @@ -2091,48 +2062,97 @@ static void clean_up_after_endstop_or_probe_move() { } stop(); return true; - } + + } // _TRIGGERED_WHEN_STOWED_TEST == deploy + #endif do_blocking_move_to(oldXpos, oldYpos, current_position[Z_AXIS]); // return to position before deploy - endstops.enable_z_probe( deploy ); + endstops.enable_z_probe(deploy); return false; } + static void do_probe_move(float z, float fr_mm_m) { + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) DEBUG_POS(">>> do_probe_move", current_position); + #endif + + // Deploy BLTouch at the start of any probe + #if ENABLED(BLTOUCH) + set_bltouch_deployed(true); + #endif + + // Move down until probe triggered + do_blocking_move_to_z(LOGICAL_Z_POSITION(z), MMM_TO_MMS(fr_mm_m)); + + // Retract BLTouch immediately after a probe + #if ENABLED(BLTOUCH) + set_bltouch_deployed(false); + #endif + + // Clear endstop flags + endstops.hit_on_purpose(); + + // Get Z where the steppers were interrupted + set_current_from_steppers_for_axis(Z_AXIS); + + // Tell the planner where we actually are + SYNC_PLAN_POSITION_KINEMATIC(); + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) DEBUG_POS("<<< do_probe_move", current_position); + #endif + } + // Do a single Z probe and return with current_position[Z_AXIS] // at the height where the probe triggered. static float run_z_probe() { + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) DEBUG_POS(">>> run_z_probe", current_position); + #endif + // Prevent stepper_inactive_time from running out and EXTRUDER_RUNOUT_PREVENT from extruding refresh_cmd_timeout(); - #if ENABLED(AUTO_BED_LEVELING_FEATURE) - planner.bed_level_matrix.set_to_identity(); - #endif - #if ENABLED(PROBE_DOUBLE_TOUCH) - do_blocking_move_to_z(-(Z_MAX_LENGTH + 10), Z_PROBE_SPEED_FAST); - endstops.hit_on_purpose(); - set_current_from_steppers_for_axis(Z_AXIS); - SYNC_PLAN_POSITION_KINEMATIC(); - // move up the retract distance - do_blocking_move_to_z(current_position[Z_AXIS] + home_bump_mm(Z_AXIS), Z_PROBE_SPEED_FAST); + // Do a first probe at the fast speed + do_probe_move(-(Z_MAX_LENGTH) - 10, Z_PROBE_SPEED_FAST); + + #if ENABLED(DEBUG_LEVELING_FEATURE) + float first_probe_z = current_position[Z_AXIS]; + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("1st Probe Z:", first_probe_z); + #endif + + // move up by the bump distance + do_blocking_move_to_z(current_position[Z_AXIS] + home_bump_mm(Z_AXIS), MMM_TO_MMS(Z_PROBE_SPEED_FAST)); + #else - // move fast, close to the bed - do_blocking_move_to_z(home_bump_mm(Z_AXIS), Z_PROBE_SPEED_FAST); + + // If the nozzle is above the travel height then + // move down quickly before doing the slow probe + float z = LOGICAL_Z_POSITION(Z_CLEARANCE_BETWEEN_PROBES); + if (zprobe_zoffset < 0) z -= zprobe_zoffset; + if (z < current_position[Z_AXIS]) + do_blocking_move_to_z(z, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); + #endif // move down slowly to find bed - do_blocking_move_to_z(current_position[Z_AXIS] -2.0*home_bump_mm(Z_AXIS), Z_PROBE_SPEED_SLOW); - endstops.hit_on_purpose(); - set_current_from_steppers_for_axis(Z_AXIS); - SYNC_PLAN_POSITION_KINEMATIC(); + do_probe_move(-(Z_MAX_LENGTH) - 10, Z_PROBE_SPEED_SLOW); #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) DEBUG_POS("run_z_probe", current_position); + if (DEBUGGING(LEVELING)) DEBUG_POS("<<< run_z_probe", current_position); #endif + // Debug: compare probe heights + #if ENABLED(PROBE_DOUBLE_TOUCH) && ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) { + SERIAL_ECHOPAIR("2nd Probe Z:", current_position[Z_AXIS]); + SERIAL_ECHOLNPAIR(" Discrepancy:", first_probe_z - current_position[Z_AXIS]); + } + #endif return current_position[Z_AXIS]; } @@ -2145,52 +2165,35 @@ static void clean_up_after_endstop_or_probe_move() { // - Raise to the BETWEEN height // - Return the probed Z position // - static float probe_pt(float x, float y, bool stow = true, int verbose_level = 1) { + static float probe_pt(const float &x, const float &y, bool stow = true, int verbose_level = 1) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR(">>> probe_pt(", x); SERIAL_ECHOPAIR(", ", y); - SERIAL_ECHOPAIR(", ", stow ? "stow" : "no stow"); - SERIAL_ECHOLNPGM(")"); + SERIAL_ECHOPAIR(", ", stow ? "" : "no "); + SERIAL_ECHOLNPGM("stow)"); DEBUG_POS("", current_position); } #endif - float old_feedrate_mm_m = feedrate_mm_m; + float old_feedrate_mm_s = feedrate_mm_s; // Ensure a minimum height before moving the probe - do_probe_raise(Z_PROBE_TRAVEL_HEIGHT); + do_probe_raise(Z_CLEARANCE_BETWEEN_PROBES); - // Move to the XY where we shall probe - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR("> do_blocking_move_to_xy(", x - (X_PROBE_OFFSET_FROM_EXTRUDER)); - SERIAL_ECHOPAIR(", ", y - (Y_PROBE_OFFSET_FROM_EXTRUDER)); - SERIAL_ECHOLNPGM(")"); - } - #endif - feedrate_mm_m = XY_PROBE_FEEDRATE_MM_M; + feedrate_mm_s = XY_PROBE_FEEDRATE_MM_S; + + // Move the probe to the given XY do_blocking_move_to_xy(x - (X_PROBE_OFFSET_FROM_EXTRUDER), y - (Y_PROBE_OFFSET_FROM_EXTRUDER)); - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) SERIAL_ECHOPGM("> "); - #endif if (DEPLOY_PROBE()) return NAN; float measured_z = run_z_probe(); - if (stow) { - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) SERIAL_ECHOPGM("> "); - #endif + if (!stow) + do_probe_raise(Z_CLEARANCE_BETWEEN_PROBES); + else if (STOW_PROBE()) return NAN; - } - else { - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> do_probe_raise"); - #endif - do_probe_raise(Z_PROBE_TRAVEL_HEIGHT); - } if (verbose_level > 2) { SERIAL_PROTOCOLPGM("Bed X: "); @@ -2206,177 +2209,317 @@ static void clean_up_after_endstop_or_probe_move() { if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< probe_pt"); #endif - feedrate_mm_m = old_feedrate_mm_m; + feedrate_mm_s = old_feedrate_mm_s; return measured_z; } #endif // HAS_BED_PROBE -#if ENABLED(AUTO_BED_LEVELING_FEATURE) +#if PLANNER_LEVELING + /** + * Turn bed leveling on or off, fixing the current + * position as-needed. + * + * Disable: Current position = physical position + * Enable: Current position = "unleveled" physical position + */ + void set_bed_leveling_enabled(bool enable=true) { + #if ENABLED(MESH_BED_LEVELING) - #if ENABLED(AUTO_BED_LEVELING_GRID) + if (enable != mbl.active()) { - #if DISABLED(DELTA) + if (!enable) + planner.apply_leveling(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS]); - static void set_bed_level_equation_lsq(double* plane_equation_coefficients) { + mbl.set_active(enable && mbl.has_mesh()); - //planner.bed_level_matrix.debug("bed level before"); + if (enable) planner.unapply_leveling(current_position); + } - #if ENABLED(DEBUG_LEVELING_FEATURE) - planner.bed_level_matrix.set_to_identity(); - if (DEBUGGING(LEVELING)) { - vector_3 uncorrected_position = planner.adjusted_position(); - DEBUG_POS(">>> set_bed_level_equation_lsq", uncorrected_position); - DEBUG_POS(">>> set_bed_level_equation_lsq", current_position); - } + #elif HAS_ABL + + if (enable != planner.abl_enabled) { + planner.abl_enabled = enable; + if (!enable) + set_current_from_steppers_for_axis( + #if ABL_PLANAR + ALL_AXES + #else + Z_AXIS + #endif + ); + else + planner.unapply_leveling(current_position); + } + + #endif + } + + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + + void set_z_fade_height(const float zfh) { + planner.z_fade_height = zfh; + planner.inverse_z_fade_height = RECIPROCAL(zfh); + + if ( + #if ENABLED(MESH_BED_LEVELING) + mbl.active() + #else + planner.abl_enabled #endif - - vector_3 planeNormal = vector_3(-plane_equation_coefficients[0], -plane_equation_coefficients[1], 1); - planner.bed_level_matrix = matrix_3x3::create_look_at(planeNormal); - - vector_3 corrected_position = planner.adjusted_position(); - current_position[X_AXIS] = corrected_position.x; - current_position[Y_AXIS] = corrected_position.y; - current_position[Z_AXIS] = corrected_position.z; - - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) DEBUG_POS("<<< set_bed_level_equation_lsq", corrected_position); - #endif - - SYNC_PLAN_POSITION_KINEMATIC(); - } - - #endif // !DELTA - - #else // !AUTO_BED_LEVELING_GRID - - static void set_bed_level_equation_3pts(float z_at_pt_1, float z_at_pt_2, float z_at_pt_3) { - - planner.bed_level_matrix.set_to_identity(); - - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - vector_3 uncorrected_position = planner.adjusted_position(); - DEBUG_POS("set_bed_level_equation_3pts", uncorrected_position); - } - #endif - - vector_3 pt1 = vector_3(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, z_at_pt_1); - vector_3 pt2 = vector_3(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, z_at_pt_2); - vector_3 pt3 = vector_3(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, z_at_pt_3); - vector_3 planeNormal = vector_3::cross(pt1 - pt2, pt3 - pt2).get_normal(); - - if (planeNormal.z < 0) { - planeNormal.x = -planeNormal.x; - planeNormal.y = -planeNormal.y; - planeNormal.z = -planeNormal.z; - } - - planner.bed_level_matrix = matrix_3x3::create_look_at(planeNormal); - vector_3 corrected_position = planner.adjusted_position(); - - current_position[X_AXIS] = corrected_position.x; - current_position[Y_AXIS] = corrected_position.y; - current_position[Z_AXIS] = corrected_position.z; - - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) DEBUG_POS("set_bed_level_equation_3pts", corrected_position); - #endif - - SYNC_PLAN_POSITION_KINEMATIC(); - } - - #endif // !AUTO_BED_LEVELING_GRID - - #if ENABLED(DELTA) - - /** - * All DELTA leveling in the Marlin uses NONLINEAR_BED_LEVELING - */ - static void extrapolate_one_point(int x, int y, int xdir, int ydir) { - if (bed_level[x][y] != 0.0) { - return; // Don't overwrite good values. - } - float a = 2 * bed_level[x + xdir][y] - bed_level[x + xdir * 2][y]; // Left to right. - float b = 2 * bed_level[x][y + ydir] - bed_level[x][y + ydir * 2]; // Front to back. - float c = 2 * bed_level[x + xdir][y + ydir] - bed_level[x + xdir * 2][y + ydir * 2]; // Diagonal. - float median = c; // Median is robust (ignores outliers). - if (a < b) { - if (b < c) median = b; - if (c < a) median = a; - } - else { // b <= a - if (c < b) median = b; - if (a < c) median = a; - } - bed_level[x][y] = median; - } - - /** - * Fill in the unprobed points (corners of circular print surface) - * using linear extrapolation, away from the center. - */ - static void extrapolate_unprobed_bed_level() { - int half = (AUTO_BED_LEVELING_GRID_POINTS - 1) / 2; - for (int y = 0; y <= half; y++) { - for (int x = 0; x <= half; x++) { - if (x + y < 3) continue; - extrapolate_one_point(half - x, half - y, x > 1 ? +1 : 0, y > 1 ? +1 : 0); - extrapolate_one_point(half + x, half - y, x > 1 ? -1 : 0, y > 1 ? +1 : 0); - extrapolate_one_point(half - x, half + y, x > 1 ? +1 : 0, y > 1 ? -1 : 0); - extrapolate_one_point(half + x, half + y, x > 1 ? -1 : 0, y > 1 ? -1 : 0); - } + ) { + set_current_from_steppers_for_axis( + #if ABL_PLANAR + ALL_AXES + #else + Z_AXIS + #endif + ); } } - /** - * Print calibration results for plotting or manual frame adjustment. - */ - static void print_bed_level() { - for (int y = 0; y < AUTO_BED_LEVELING_GRID_POINTS; y++) { - for (int x = 0; x < AUTO_BED_LEVELING_GRID_POINTS; x++) { - SERIAL_PROTOCOL_F(bed_level[x][y], 2); - SERIAL_PROTOCOLCHAR(' '); - } - SERIAL_EOL; - } - } + #endif // LEVELING_FADE_HEIGHT - /** - * Reset calibration results to zero. - */ - void reset_bed_level() { + /** + * Reset calibration results to zero. + */ + void reset_bed_level() { + #if ENABLED(MESH_BED_LEVELING) + if (mbl.has_mesh()) { + set_bed_leveling_enabled(false); + mbl.reset(); + mbl.set_has_mesh(false); + } + #else + planner.abl_enabled = false; #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("reset_bed_level"); #endif - for (int y = 0; y < AUTO_BED_LEVELING_GRID_POINTS; y++) { - for (int x = 0; x < AUTO_BED_LEVELING_GRID_POINTS; x++) { - bed_level[x][y] = 0.0; - } + #if ABL_PLANAR + planner.bed_level_matrix.set_to_identity(); + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + for (uint8_t x = 0; x < ABL_GRID_POINTS_X; x++) + for (uint8_t y = 0; y < ABL_GRID_POINTS_Y; y++) + bed_level_grid[x][y] = 1000.0; + #endif + #endif + } + +#endif // PLANNER_LEVELING + +#if ENABLED(AUTO_BED_LEVELING_BILINEAR) + + /** + * Extrapolate a single point from its neighbors + */ + static void extrapolate_one_point(uint8_t x, uint8_t y, int8_t xdir, int8_t ydir) { + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) { + SERIAL_ECHOPGM("Extrapolate ["); + if (x < 10) SERIAL_CHAR(' '); + SERIAL_ECHO((int)x); + SERIAL_CHAR(xdir ? (xdir > 0 ? '+' : '-') : ' '); + SERIAL_CHAR(' '); + if (y < 10) SERIAL_CHAR(' '); + SERIAL_ECHO((int)y); + SERIAL_CHAR(ydir ? (ydir > 0 ? '+' : '-') : ' '); + SERIAL_CHAR(']'); } + #endif + if (bed_level_grid[x][y] < 999.0) { + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM(" (done)"); + #endif + return; // Don't overwrite good values. } + SERIAL_EOL; - #endif // DELTA + // Get X neighbors, Y neighbors, and XY neighbors + float a1 = bed_level_grid[x + xdir][y], a2 = bed_level_grid[x + xdir * 2][y], + b1 = bed_level_grid[x][y + ydir], b2 = bed_level_grid[x][y + ydir * 2], + c1 = bed_level_grid[x + xdir][y + ydir], c2 = bed_level_grid[x + xdir * 2][y + ydir * 2]; + + // Treat far unprobed points as zero, near as equal to far + if (a2 > 999.0) a2 = 0.0; if (a1 > 999.0) a1 = a2; + if (b2 > 999.0) b2 = 0.0; if (b1 > 999.0) b1 = b2; + if (c2 > 999.0) c2 = 0.0; if (c1 > 999.0) c1 = c2; + + float a = 2 * a1 - a2, b = 2 * b1 - b2, c = 2 * c1 - c2; + + // Take the average intstead of the median + bed_level_grid[x][y] = (a + b + c) / 3.0; + + // Median is robust (ignores outliers). + // bed_level_grid[x][y] = (a < b) ? ((b < c) ? b : (c < a) ? a : c) + // : ((c < b) ? b : (a < c) ? a : c); + } + + //Enable this if your SCARA uses 180° of total area + //#define EXTRAPOLATE_FROM_EDGE + + #if ENABLED(EXTRAPOLATE_FROM_EDGE) + #if ABL_GRID_POINTS_X < ABL_GRID_POINTS_Y + #define HALF_IN_X + #elif ABL_GRID_POINTS_Y < ABL_GRID_POINTS_X + #define HALF_IN_Y + #endif + #endif + + /** + * Fill in the unprobed points (corners of circular print surface) + * using linear extrapolation, away from the center. + */ + static void extrapolate_unprobed_bed_level() { + #ifdef HALF_IN_X + const uint8_t ctrx2 = 0, xlen = ABL_GRID_POINTS_X - 1; + #else + const uint8_t ctrx1 = (ABL_GRID_POINTS_X - 1) / 2, // left-of-center + ctrx2 = ABL_GRID_POINTS_X / 2, // right-of-center + xlen = ctrx1; + #endif + + #ifdef HALF_IN_Y + const uint8_t ctry2 = 0, ylen = ABL_GRID_POINTS_Y - 1; + #else + const uint8_t ctry1 = (ABL_GRID_POINTS_Y - 1) / 2, // top-of-center + ctry2 = ABL_GRID_POINTS_Y / 2, // bottom-of-center + ylen = ctry1; + #endif + + for (uint8_t xo = 0; xo <= xlen; xo++) + for (uint8_t yo = 0; yo <= ylen; yo++) { + uint8_t x2 = ctrx2 + xo, y2 = ctry2 + yo; + #ifndef HALF_IN_X + uint8_t x1 = ctrx1 - xo; + #endif + #ifndef HALF_IN_Y + uint8_t y1 = ctry1 - yo; + #ifndef HALF_IN_X + extrapolate_one_point(x1, y1, +1, +1); // left-below + + + #endif + extrapolate_one_point(x2, y1, -1, +1); // right-below - + + #endif + #ifndef HALF_IN_X + extrapolate_one_point(x1, y2, +1, -1); // left-above + - + #endif + extrapolate_one_point(x2, y2, -1, -1); // right-above - - + } + + } + + /** + * Print calibration results for plotting or manual frame adjustment. + */ + static void print_bed_level() { + SERIAL_ECHOPGM("Bilinear Leveling Grid:\n "); + for (uint8_t x = 0; x < ABL_GRID_POINTS_X; x++) { + SERIAL_PROTOCOLPGM(" "); + if (x < 10) SERIAL_PROTOCOLCHAR(' '); + SERIAL_PROTOCOL((int)x); + } + SERIAL_EOL; + for (uint8_t y = 0; y < ABL_GRID_POINTS_Y; y++) { + if (y < 10) SERIAL_PROTOCOLCHAR(' '); + SERIAL_PROTOCOL((int)y); + for (uint8_t x = 0; x < ABL_GRID_POINTS_X; x++) { + SERIAL_PROTOCOLCHAR(' '); + float offset = bed_level_grid[x][y]; + if (offset < 999.0) { + if (offset > 0) SERIAL_CHAR('+'); + SERIAL_PROTOCOL_F(offset, 2); + } + else + SERIAL_PROTOCOLPGM(" ===="); + } + SERIAL_EOL; + } + SERIAL_EOL; + } + +#endif // AUTO_BED_LEVELING_BILINEAR -#endif // AUTO_BED_LEVELING_FEATURE /** - * Home an individual axis + * Home an individual linear axis + */ +static void do_homing_move(const AxisEnum axis, float distance, float fr_mm_s=0.0) { + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) { + SERIAL_ECHOPAIR(">>> do_homing_move(", axis_codes[axis]); + SERIAL_ECHOPAIR(", ", distance); + SERIAL_ECHOPAIR(", ", fr_mm_s); + SERIAL_CHAR(')'); + SERIAL_EOL; + } + #endif + + #if HOMING_Z_WITH_PROBE && ENABLED(BLTOUCH) + bool deploy_bltouch = (axis == Z_AXIS && distance < 0); + if (deploy_bltouch) set_bltouch_deployed(true); + #endif + + // Tell the planner we're at Z=0 + current_position[axis] = 0; + + #if IS_SCARA + SYNC_PLAN_POSITION_KINEMATIC(); + current_position[axis] = distance; + inverse_kinematics(current_position); + planner.buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], current_position[E_AXIS], fr_mm_s ? fr_mm_s : homing_feedrate_mm_s[axis], active_extruder); + #else + sync_plan_position(); + current_position[axis] = distance; + planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], fr_mm_s ? fr_mm_s : homing_feedrate_mm_s[axis], active_extruder); + #endif + + stepper.synchronize(); + + #if HOMING_Z_WITH_PROBE && ENABLED(BLTOUCH) + if (deploy_bltouch) set_bltouch_deployed(false); + #endif + + endstops.hit_on_purpose(); + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) { + SERIAL_ECHOPAIR("<<< do_homing_move(", axis_codes[axis]); + SERIAL_CHAR(')'); + SERIAL_EOL; + } + #endif +} + +/** + * Home an individual "raw axis" to its endstop. + * This applies to XYZ on Cartesian and Core robots, and + * to the individual ABC steppers on DELTA and SCARA. + * + * At the end of the procedure the axis is marked as + * homed and the current position of that axis is updated. + * Kinematic robots should wait till all axes are homed + * before updating the current position. */ #define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS) static void homeaxis(AxisEnum axis) { - #define HOMEAXIS_DO(LETTER) \ - ((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1)) - if (!(axis == X_AXIS ? HOMEAXIS_DO(X) : axis == Y_AXIS ? HOMEAXIS_DO(Y) : axis == Z_AXIS ? HOMEAXIS_DO(Z) : 0)) return; + #if IS_SCARA + // Only Z homing (with probe) is permitted + if (axis != Z_AXIS) { BUZZ(100, 880); return; } + #else + #define CAN_HOME(A) \ + (axis == A##_AXIS && ((A##_MIN_PIN > -1 && A##_HOME_DIR < 0) || (A##_MAX_PIN > -1 && A##_HOME_DIR > 0))) + if (!CAN_HOME(X) && !CAN_HOME(Y) && !CAN_HOME(Z)) return; + #endif #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR(">>> homeaxis(", axis); - SERIAL_ECHOLNPGM(")"); + SERIAL_ECHOPAIR(">>> homeaxis(", axis_codes[axis]); + SERIAL_CHAR(')'); + SERIAL_EOL; } #endif @@ -2387,44 +2530,43 @@ static void homeaxis(AxisEnum axis) { home_dir(axis); // Homing Z towards the bed? Deploy the Z probe or endstop. - #if HAS_BED_PROBE && DISABLED(Z_MIN_PROBE_ENDSTOP) - if (axis == Z_AXIS && axis_home_dir < 0) { - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) SERIAL_ECHOPGM("> "); - #endif - if (DEPLOY_PROBE()) return; - } + #if HOMING_Z_WITH_PROBE + if (axis == Z_AXIS && DEPLOY_PROBE()) return; #endif - // Set the axis position as setup for the move - current_position[axis] = 0; - sync_plan_position(); - // Set a flag for Z motor locking #if ENABLED(Z_DUAL_ENDSTOPS) if (axis == Z_AXIS) stepper.set_homing_flag(true); #endif - // Move towards the endstop until an endstop is triggered - line_to_axis_pos(axis, 1.5 * max_length(axis) * axis_home_dir); - - // Set the axis position as setup for the move - current_position[axis] = 0; - sync_plan_position(); - - // Move away from the endstop by the axis HOME_BUMP_MM - line_to_axis_pos(axis, -home_bump_mm(axis) * axis_home_dir); - - // Move slowly towards the endstop until triggered - line_to_axis_pos(axis, 2 * home_bump_mm(axis) * axis_home_dir, get_homing_bump_feedrate(axis)); - - // reset current_position to 0 to reflect hitting endpoint - current_position[axis] = 0; - sync_plan_position(); - + // Fast move towards endstop until triggered #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) DEBUG_POS("> TRIGGER ENDSTOP", current_position); + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("Home 1 Fast:"); #endif + do_homing_move(axis, 1.5 * max_length(axis) * axis_home_dir); + + // When homing Z with probe respect probe clearance + const float bump = axis_home_dir * ( + #if HOMING_Z_WITH_PROBE + (axis == Z_AXIS) ? max(Z_CLEARANCE_BETWEEN_PROBES, home_bump_mm(Z_AXIS)) : + #endif + home_bump_mm(axis) + ); + + // If a second homing move is configured... + if (bump) { + // Move away from the endstop by the axis HOME_BUMP_MM + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("Move Away:"); + #endif + do_homing_move(axis, -bump); + + // Slow move towards endstop until triggered + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("Home 2 Slow:"); + #endif + do_homing_move(axis, 2 * bump, get_homing_bump_feedrate(axis)); + } #if ENABLED(Z_DUAL_ENDSTOPS) if (axis == Z_AXIS) { @@ -2440,57 +2582,60 @@ static void homeaxis(AxisEnum axis) { if (lockZ1) stepper.set_z_lock(true); else stepper.set_z2_lock(true); // Move to the adjusted endstop height - line_to_axis_pos(axis, adj); + do_homing_move(axis, adj); if (lockZ1) stepper.set_z_lock(false); else stepper.set_z2_lock(false); stepper.set_homing_flag(false); } // Z_AXIS #endif - #if ENABLED(DELTA) + #if IS_SCARA + + set_axis_is_at_home(axis); + SYNC_PLAN_POSITION_KINEMATIC(); + + #elif ENABLED(DELTA) + + // Delta has already moved all three towers up in G28 + // so here it re-homes each tower in turn. + // Delta homing treats the axes as normal linear axes. + // retrace by the amount specified in endstop_adj - if (endstop_adj[axis] * axis_home_dir < 0) { + if (endstop_adj[axis] * Z_HOME_DIR < 0) { #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR("> endstop_adj = ", endstop_adj[axis]); - DEBUG_POS("", current_position); - } + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("endstop_adj:"); #endif - line_to_axis_pos(axis, endstop_adj[axis]); + do_homing_move(axis, endstop_adj[axis]); } + + #else + + // For cartesian/core machines, + // set the axis to its home position + set_axis_is_at_home(axis); + sync_plan_position(); + + destination[axis] = current_position[axis]; + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) DEBUG_POS("> AFTER set_axis_is_at_home", current_position); + #endif + #endif - // Set the axis position to its home position (plus home offsets) - set_axis_is_at_home(axis); - - SYNC_PLAN_POSITION_KINEMATIC(); - - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) DEBUG_POS("> AFTER set_axis_is_at_home", current_position); - #endif - - destination[axis] = current_position[axis]; - endstops.hit_on_purpose(); // clear endstop hit flags - axis_known_position[axis] = true; - axis_homed[axis] = true; - // Put away the Z probe - #if HAS_BED_PROBE && DISABLED(Z_MIN_PROBE_ENDSTOP) - if (axis == Z_AXIS && axis_home_dir < 0) { - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) SERIAL_ECHOPGM("> "); - #endif - if (STOW_PROBE()) return; - } + #if HOMING_Z_WITH_PROBE + if (axis == Z_AXIS && STOW_PROBE()) return; #endif #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR("<<< homeaxis(", axis); - SERIAL_ECHOLNPGM(")"); + SERIAL_ECHOPAIR("<<< homeaxis(", axis_codes[axis]); + SERIAL_CHAR(')'); + SERIAL_EOL; } #endif -} +} // homeaxis() #if ENABLED(FWRETRACT) @@ -2498,13 +2643,13 @@ static void homeaxis(AxisEnum axis) { if (retracting == retracted[active_extruder]) return; - float old_feedrate_mm_m = feedrate_mm_m; + float old_feedrate_mm_s = feedrate_mm_s; set_destination_to_current(); if (retracting) { - feedrate_mm_m = MMS_TO_MMM(retract_feedrate_mm_s); + feedrate_mm_s = retract_feedrate_mm_s; current_position[E_AXIS] += (swapping ? retract_length_swap : retract_length) / volumetric_multiplier[active_extruder]; sync_plan_position_e(); prepare_move_to_destination(); @@ -2522,14 +2667,14 @@ static void homeaxis(AxisEnum axis) { SYNC_PLAN_POSITION_KINEMATIC(); } - feedrate_mm_m = MMS_TO_MMM(retract_recover_feedrate_mm_s); + feedrate_mm_s = retract_recover_feedrate_mm_s; float move_e = swapping ? retract_length_swap + retract_recover_length_swap : retract_length + retract_recover_length; current_position[E_AXIS] -= move_e / volumetric_multiplier[active_extruder]; sync_plan_position_e(); prepare_move_to_destination(); } - feedrate_mm_m = old_feedrate_mm_m; + feedrate_mm_s = old_feedrate_mm_s; retracted[active_extruder] = retracting; } // retract() @@ -2540,30 +2685,36 @@ static void homeaxis(AxisEnum axis) { void normalize_mix() { float mix_total = 0.0; - for (int i = 0; i < MIXING_STEPPERS; i++) { - float v = mixing_factor[i]; - if (v < 0) v = mixing_factor[i] = 0; - mix_total += v; - } + for (int i = 0; i < MIXING_STEPPERS; i++) mix_total += RECIPROCAL(mixing_factor[i]); // Scale all values if they don't add up to ~1.0 - if (mix_total < 0.9999 || mix_total > 1.0001) { + if (!NEAR(mix_total, 1.0)) { SERIAL_PROTOCOLLNPGM("Warning: Mix factors must add up to 1.0. Scaling."); - float mix_scale = 1.0 / mix_total; - for (int i = 0; i < MIXING_STEPPERS; i++) - mixing_factor[i] *= mix_scale; + for (int i = 0; i < MIXING_STEPPERS; i++) mixing_factor[i] *= mix_total; } } #if ENABLED(DIRECT_MIXING_IN_G1) // Get mixing parameters from the GCode - // Factors that are left out are set to 0 // The total "must" be 1.0 (but it will be normalized) + // If no mix factors are given, the old mix is preserved void gcode_get_mix() { const char* mixing_codes = "ABCDHI"; - for (int i = 0; i < MIXING_STEPPERS; i++) - mixing_factor[i] = code_seen(mixing_codes[i]) ? code_value_float() : 0; - - normalize_mix(); + byte mix_bits = 0; + for (uint8_t i = 0; i < MIXING_STEPPERS; i++) { + if (code_seen(mixing_codes[i])) { + SBI(mix_bits, i); + float v = code_value_float(); + NOLESS(v, 0.0); + mixing_factor[i] = RECIPROCAL(v); + } + } + // If any mixing factors were included, clear the rest + // If none were included, preserve the last mix + if (mix_bits) { + for (uint8_t i = 0; i < MIXING_STEPPERS; i++) + if (!TEST(mix_bits, i)) mixing_factor[i] = 0.0; + normalize_mix(); + } } #endif @@ -2591,7 +2742,7 @@ void gcode_get_destination() { } if (code_seen('F') && code_value_linear_units() > 0.0) - feedrate_mm_m = code_value_linear_units(); + feedrate_mm_s = MMM_TO_MMS(code_value_linear_units()); #if ENABLED(PRINTCOUNTER) if (!DEBUGGING(DRYRUN)) @@ -2606,9 +2757,9 @@ void gcode_get_destination() { void unknown_command_error() { SERIAL_ECHO_START; - SERIAL_ECHOPGM(MSG_UNKNOWN_COMMAND); - SERIAL_ECHO(current_command); - SERIAL_ECHOLNPGM("\""); + SERIAL_ECHOPAIR(MSG_UNKNOWN_COMMAND, current_command); + SERIAL_CHAR('"'); + SERIAL_EOL; } #if ENABLED(HOST_KEEPALIVE_FEATURE) @@ -2644,10 +2795,50 @@ void unknown_command_error() { #endif //HOST_KEEPALIVE_FEATURE +bool position_is_reachable(float target[XYZ] + #if HAS_BED_PROBE + , bool by_probe=false + #endif +) { + float dx = RAW_X_POSITION(target[X_AXIS]), + dy = RAW_Y_POSITION(target[Y_AXIS]); + + #if HAS_BED_PROBE + if (by_probe) { + dx -= X_PROBE_OFFSET_FROM_EXTRUDER; + dy -= Y_PROBE_OFFSET_FROM_EXTRUDER; + } + #endif + + #if IS_SCARA + #if MIDDLE_DEAD_ZONE_R > 0 + const float R2 = HYPOT2(dx - SCARA_OFFSET_X, dy - SCARA_OFFSET_Y); + return R2 >= sq(float(MIDDLE_DEAD_ZONE_R)) && R2 <= sq(L1 + L2); + #else + return HYPOT2(dx - SCARA_OFFSET_X, dy - SCARA_OFFSET_Y) <= sq(L1 + L2); + #endif + #elif ENABLED(DELTA) + return HYPOT2(dx, dy) <= sq(DELTA_PRINTABLE_RADIUS); + #else + const float dz = RAW_Z_POSITION(target[Z_AXIS]); + return dx >= X_MIN_POS - 0.0001 && dx <= X_MAX_POS + 0.0001 + && dy >= Y_MIN_POS - 0.0001 && dy <= Y_MAX_POS + 0.0001 + && dz >= Z_MIN_POS - 0.0001 && dz <= Z_MAX_POS + 0.0001; + #endif +} + +/************************************************** + ***************** GCode Handlers ***************** + **************************************************/ + /** * G0, G1: Coordinated movement of X Y Z E axes */ -inline void gcode_G0_G1() { +inline void gcode_G0_G1( + #if IS_SCARA + bool fast_move=false + #endif +) { if (IsRunning()) { gcode_get_destination(); // For X Y Z E F @@ -2666,13 +2857,36 @@ inline void gcode_G0_G1() { #endif //FWRETRACT - prepare_move_to_destination(); + #if IS_SCARA + fast_move ? prepare_uninterpolated_move_to_destination() : prepare_move_to_destination(); + #else + prepare_move_to_destination(); + #endif } } /** * G2: Clockwise Arc * G3: Counterclockwise Arc + * + * This command has two forms: IJ-form and R-form. + * + * - I specifies an X offset. J specifies a Y offset. + * At least one of the IJ parameters is required. + * X and Y can be omitted to do a complete circle. + * The given XY is not error-checked. The arc ends + * based on the angle of the destination. + * Mixing I or J with R will throw an error. + * + * - R specifies the radius. X or Y is required. + * Omitting both X and Y will throw an error. + * X or Y must differ from the current XY. + * Mixing R with I or J will throw an error. + * + * Examples: + * + * G2 I10 ; CW circle centered at X+10 + * G3 X20 Y12 R14 ; CCW circle with r=14 ending at X20 Y12 */ #if ENABLED(ARC_SUPPORT) inline void gcode_G2_G3(bool clockwise) { @@ -2689,16 +2903,38 @@ inline void gcode_G0_G1() { relative_mode = relative_mode_backup; #endif - // Center of arc as offset from current_position - float arc_offset[2] = { - code_seen('I') ? code_value_axis_units(X_AXIS) : 0, - code_seen('J') ? code_value_axis_units(Y_AXIS) : 0 - }; + float arc_offset[2] = { 0.0, 0.0 }; + if (code_seen('R')) { + const float r = code_value_axis_units(X_AXIS), + x1 = current_position[X_AXIS], y1 = current_position[Y_AXIS], + x2 = destination[X_AXIS], y2 = destination[Y_AXIS]; + if (r && (x2 != x1 || y2 != y1)) { + const float e = clockwise ^ (r < 0) ? -1 : 1, // clockwise -1/1, counterclockwise 1/-1 + dx = x2 - x1, dy = y2 - y1, // X and Y differences + d = HYPOT(dx, dy), // Linear distance between the points + h = sqrt(sq(r) - sq(d * 0.5)), // Distance to the arc pivot-point + mx = (x1 + x2) * 0.5, my = (y1 + y2) * 0.5, // Point between the two points + sx = -dy / d, sy = dx / d, // Slope of the perpendicular bisector + cx = mx + e * h * sx, cy = my + e * h * sy; // Pivot-point of the arc + arc_offset[X_AXIS] = cx - x1; + arc_offset[Y_AXIS] = cy - y1; + } + } + else { + if (code_seen('I')) arc_offset[X_AXIS] = code_value_axis_units(X_AXIS); + if (code_seen('J')) arc_offset[Y_AXIS] = code_value_axis_units(Y_AXIS); + } - // Send an arc to the planner - plan_arc(destination, arc_offset, clockwise); - - refresh_cmd_timeout(); + if (arc_offset[0] || arc_offset[1]) { + // Send an arc to the planner + plan_arc(destination, arc_offset, clockwise); + refresh_cmd_timeout(); + } + else { + // Bad arguments + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM(MSG_ERR_ARC_ARGS); + } } } #endif @@ -2792,16 +3028,12 @@ inline void gcode_G4() { /** * G20: Set input mode to inches */ - inline void gcode_G20() { - set_input_linear_units(LINEARUNIT_INCH); - } + inline void gcode_G20() { set_input_linear_units(LINEARUNIT_INCH); } /** * G21: Set input mode to millimeters */ - inline void gcode_G21() { - set_input_linear_units(LINEARUNIT_MM); - } + inline void gcode_G21() { set_input_linear_units(LINEARUNIT_MM); } #endif #if ENABLED(NOZZLE_PARK_FEATURE) @@ -2835,9 +3067,9 @@ inline void gcode_G4() { float mlx = max_length(X_AXIS), mly = max_length(Y_AXIS), mlratio = mlx > mly ? mly / mlx : mlx / mly, - fr_mm_m = min(homing_feedrate_mm_m[X_AXIS], homing_feedrate_mm_m[Y_AXIS]) * sqrt(sq(mlratio) + 1.0); + fr_mm_s = min(homing_feedrate_mm_s[X_AXIS], homing_feedrate_mm_s[Y_AXIS]) * sqrt(sq(mlratio) + 1.0); - do_blocking_move_to_xy(1.5 * mlx * x_axis_home_dir, 1.5 * mly * home_dir(Y_AXIS), fr_mm_m); + do_blocking_move_to_xy(1.5 * mlx * x_axis_home_dir, 1.5 * mly * home_dir(Y_AXIS), fr_mm_s); endstops.hit_on_purpose(); // clear endstop hit flags current_position[X_AXIS] = current_position[Y_AXIS] = 0.0; @@ -2845,6 +3077,215 @@ inline void gcode_G4() { #endif // QUICK_HOME +#if ENABLED(DEBUG_LEVELING_FEATURE) + + void log_machine_info() { + SERIAL_ECHOPGM("Machine Type: "); + #if ENABLED(DELTA) + SERIAL_ECHOLNPGM("Delta"); + #elif IS_SCARA + SERIAL_ECHOLNPGM("SCARA"); + #elif IS_CORE + SERIAL_ECHOLNPGM("Core"); + #else + SERIAL_ECHOLNPGM("Cartesian"); + #endif + + SERIAL_ECHOPGM("Probe: "); + #if ENABLED(FIX_MOUNTED_PROBE) + SERIAL_ECHOLNPGM("FIX_MOUNTED_PROBE"); + #elif ENABLED(BLTOUCH) + SERIAL_ECHOLNPGM("BLTOUCH"); + #elif HAS_Z_SERVO_ENDSTOP + SERIAL_ECHOLNPGM("SERVO PROBE"); + #elif ENABLED(Z_PROBE_SLED) + SERIAL_ECHOLNPGM("Z_PROBE_SLED"); + #elif ENABLED(Z_PROBE_ALLEN_KEY) + SERIAL_ECHOLNPGM("Z_PROBE_ALLEN_KEY"); + #else + SERIAL_ECHOLNPGM("NONE"); + #endif + + #if HAS_BED_PROBE + SERIAL_ECHOPAIR("Probe Offset X:", X_PROBE_OFFSET_FROM_EXTRUDER); + SERIAL_ECHOPAIR(" Y:", Y_PROBE_OFFSET_FROM_EXTRUDER); + SERIAL_ECHOPAIR(" Z:", zprobe_zoffset); + #if (X_PROBE_OFFSET_FROM_EXTRUDER > 0) + SERIAL_ECHOPGM(" (Right"); + #elif (X_PROBE_OFFSET_FROM_EXTRUDER < 0) + SERIAL_ECHOPGM(" (Left"); + #elif (Y_PROBE_OFFSET_FROM_EXTRUDER != 0) + SERIAL_ECHOPGM(" (Middle"); + #else + SERIAL_ECHOPGM(" (Aligned With"); + #endif + #if (Y_PROBE_OFFSET_FROM_EXTRUDER > 0) + SERIAL_ECHOPGM("-Back"); + #elif (Y_PROBE_OFFSET_FROM_EXTRUDER < 0) + SERIAL_ECHOPGM("-Front"); + #elif (X_PROBE_OFFSET_FROM_EXTRUDER != 0) + SERIAL_ECHOPGM("-Center"); + #endif + if (zprobe_zoffset < 0) + SERIAL_ECHOPGM(" & Below"); + else if (zprobe_zoffset > 0) + SERIAL_ECHOPGM(" & Above"); + else + SERIAL_ECHOPGM(" & Same Z as"); + SERIAL_ECHOLNPGM(" Nozzle)"); + #endif + + #if HAS_ABL + SERIAL_ECHOPGM("Auto Bed Leveling: "); + #if ENABLED(AUTO_BED_LEVELING_LINEAR) + SERIAL_ECHOPGM("LINEAR"); + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + SERIAL_ECHOPGM("BILINEAR"); + #elif ENABLED(AUTO_BED_LEVELING_3POINT) + SERIAL_ECHOPGM("3POINT"); + #endif + if (planner.abl_enabled) { + SERIAL_ECHOLNPGM(" (enabled)"); + #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_3POINT) + float diff[XYZ] = { + stepper.get_axis_position_mm(X_AXIS) - current_position[X_AXIS], + stepper.get_axis_position_mm(Y_AXIS) - current_position[Y_AXIS], + stepper.get_axis_position_mm(Z_AXIS) - current_position[Z_AXIS] + }; + SERIAL_ECHOPGM("ABL Adjustment X"); + if (diff[X_AXIS] > 0) SERIAL_CHAR('+'); + SERIAL_ECHO(diff[X_AXIS]); + SERIAL_ECHOPGM(" Y"); + if (diff[Y_AXIS] > 0) SERIAL_CHAR('+'); + SERIAL_ECHO(diff[Y_AXIS]); + SERIAL_ECHOPGM(" Z"); + if (diff[Z_AXIS] > 0) SERIAL_CHAR('+'); + SERIAL_ECHO(diff[Z_AXIS]); + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + SERIAL_ECHOPAIR("ABL Adjustment Z", bilinear_z_offset(current_position)); + #endif + } + SERIAL_EOL; + #elif ENABLED(MESH_BED_LEVELING) + SERIAL_ECHOPGM("Mesh Bed Leveling"); + if (mbl.active()) { + float lz = current_position[Z_AXIS]; + planner.apply_leveling(current_position[X_AXIS], current_position[Y_AXIS], lz); + SERIAL_ECHOLNPGM(" (enabled)"); + SERIAL_ECHOPAIR("MBL Adjustment Z", lz); + } + SERIAL_EOL; + #endif + + } + +#endif // DEBUG_LEVELING_FEATURE + +#if ENABLED(DELTA) + + /** + * A delta can only safely home all axes at the same time + * This is like quick_home_xy() but for 3 towers. + */ + inline void home_delta() { + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) DEBUG_POS(">>> home_delta", current_position); + #endif + // Init the current position of all carriages to 0,0,0 + ZERO(current_position); + sync_plan_position(); + + // Move all carriages together linearly until an endstop is hit. + current_position[X_AXIS] = current_position[Y_AXIS] = current_position[Z_AXIS] = (Z_MAX_LENGTH + 10); + feedrate_mm_s = homing_feedrate_mm_s[X_AXIS]; + line_to_current_position(); + stepper.synchronize(); + endstops.hit_on_purpose(); // clear endstop hit flags + + // At least one carriage has reached the top. + // Now re-home each carriage separately. + HOMEAXIS(A); + HOMEAXIS(B); + HOMEAXIS(C); + + // Set all carriages to their home positions + // Do this here all at once for Delta, because + // XYZ isn't ABC. Applying this per-tower would + // give the impression that they are the same. + LOOP_XYZ(i) set_axis_is_at_home((AxisEnum)i); + + SYNC_PLAN_POSITION_KINEMATIC(); + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) DEBUG_POS("<<< home_delta", current_position); + #endif + } + +#endif // DELTA + +#if ENABLED(Z_SAFE_HOMING) + + inline void home_z_safely() { + + // Disallow Z homing if X or Y are unknown + if (!axis_known_position[X_AXIS] || !axis_known_position[Y_AXIS]) { + LCD_MESSAGEPGM(MSG_ERR_Z_HOMING); + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM(MSG_ERR_Z_HOMING); + return; + } + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("Z_SAFE_HOMING >>>"); + #endif + + SYNC_PLAN_POSITION_KINEMATIC(); + + /** + * Move the Z probe (or just the nozzle) to the safe homing point + */ + destination[X_AXIS] = LOGICAL_X_POSITION(Z_SAFE_HOMING_X_POINT); + destination[Y_AXIS] = LOGICAL_Y_POSITION(Z_SAFE_HOMING_Y_POINT); + destination[Z_AXIS] = current_position[Z_AXIS]; // Z is already at the right height + + if (position_is_reachable( + destination + #if HOMING_Z_WITH_PROBE + , true + #endif + ) + ) { + + #if HOMING_Z_WITH_PROBE + destination[X_AXIS] -= X_PROBE_OFFSET_FROM_EXTRUDER; + destination[Y_AXIS] -= Y_PROBE_OFFSET_FROM_EXTRUDER; + #endif + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) DEBUG_POS("Z_SAFE_HOMING", destination); + #endif + + // This causes the carriage on Dual X to unpark + #if ENABLED(DUAL_X_CARRIAGE) + active_extruder_parked = false; + #endif + + do_blocking_move_to_xy(destination[X_AXIS], destination[Y_AXIS]); + HOMEAXIS(Z); + } + else { + LCD_MESSAGEPGM(MSG_ZPROBE_OUT); + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM(MSG_ZPROBE_OUT); + } + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< Z_SAFE_HOMING"); + #endif + } + +#endif // Z_SAFE_HOMING + /** * G28: Home all axes according to settings * @@ -2863,18 +3304,18 @@ inline void gcode_G4() { inline void gcode_G28() { #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM(">>> gcode_G28"); + if (DEBUGGING(LEVELING)) { + SERIAL_ECHOLNPGM(">>> gcode_G28"); + log_machine_info(); + } #endif // Wait for planner moves to finish! stepper.synchronize(); // For auto bed leveling, clear the level matrix - #if ENABLED(AUTO_BED_LEVELING_FEATURE) - planner.bed_level_matrix.set_to_identity(); - #if ENABLED(DELTA) - reset_bed_level(); - #endif + #if HAS_ABL + reset_bed_level(); #endif // Always home with tool 0 active @@ -2897,13 +3338,15 @@ inline void gcode_G28() { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("MBL was active"); #endif - // Save known Z position if already homed + // Use known Z position if already homed if (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) { + set_bed_leveling_enabled(false); pre_home_z = current_position[Z_AXIS]; - pre_home_z += mbl.get_z(RAW_CURRENT_POSITION(X_AXIS), RAW_CURRENT_POSITION(Y_AXIS)); } - mbl.set_active(false); - current_position[Z_AXIS] = pre_home_z; + else { + mbl.set_active(false); + current_position[Z_AXIS] = pre_home_z; + } #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("Set Z to pre_home_z", current_position); #endif @@ -2916,35 +3359,9 @@ inline void gcode_G28() { #endif endstops.enable(true); // Enable endstops for next homing move - #if ENABLED(DELTA) - /** - * A delta can only safely home all axes at the same time - */ - // Pretend the current position is 0,0,0 - // This is like quick_home_xy() but for 3 towers. - current_position[X_AXIS] = current_position[Y_AXIS] = current_position[Z_AXIS] = 0.0; - sync_plan_position(); - - // Move all carriages up together until the first endstop is hit. - current_position[X_AXIS] = current_position[Y_AXIS] = current_position[Z_AXIS] = 3.0 * (Z_MAX_LENGTH); - feedrate_mm_m = 1.732 * homing_feedrate_mm_m[X_AXIS]; - line_to_current_position(); - stepper.synchronize(); - endstops.hit_on_purpose(); // clear endstop hit flags - current_position[X_AXIS] = current_position[Y_AXIS] = current_position[Z_AXIS] = 0.0; - - // take care of back off and rehome. Now one carriage is at the top. - HOMEAXIS(X); - HOMEAXIS(Y); - HOMEAXIS(Z); - - SYNC_PLAN_POSITION_KINEMATIC(); - - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) DEBUG_POS("(DELTA)", current_position); - #endif + home_delta(); #else // NOT DELTA @@ -2971,10 +3388,8 @@ inline void gcode_G28() { if (destination[Z_AXIS] > current_position[Z_AXIS]) { #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR("Raise Z (before homing) to ", destination[Z_AXIS]); - SERIAL_EOL; - } + if (DEBUGGING(LEVELING)) + SERIAL_ECHOLNPAIR("Raise Z (before homing) to ", destination[Z_AXIS]); #endif do_blocking_move_to_z(destination[Z_AXIS]); @@ -3003,20 +3418,31 @@ inline void gcode_G28() { // Home X if (home_all_axis || homeX) { + #if ENABLED(DUAL_X_CARRIAGE) - int tmp_extruder = active_extruder; - active_extruder = !active_extruder; + + // Always home the 2nd (right) extruder first + active_extruder = 1; HOMEAXIS(X); + + // Remember this extruder's position for later tool change inactive_extruder_x_pos = RAW_X_POSITION(current_position[X_AXIS]); - active_extruder = tmp_extruder; + + // Home the 1st (left) extruder + active_extruder = 0; HOMEAXIS(X); - // reset state used by the different modes + + // Consider the active extruder to be parked memcpy(raised_parked_position, current_position, sizeof(raised_parked_position)); delayed_move_time = 0; active_extruder_parked = true; + #else + HOMEAXIS(X); + #endif + #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("> homeX", current_position); #endif @@ -3034,97 +3460,28 @@ inline void gcode_G28() { // Home Z last if homing towards the bed #if Z_HOME_DIR < 0 - if (home_all_axis || homeZ) { - #if ENABLED(Z_SAFE_HOMING) - - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - SERIAL_ECHOLNPGM("> Z_SAFE_HOMING >>>"); - } - #endif - - if (home_all_axis) { - - /** - * At this point we already have Z at Z_HOMING_HEIGHT height - * No need to move Z any more as this height should already be safe - * enough to reach Z_SAFE_HOMING XY positions. - * Just make sure the planner is in sync. - */ - SYNC_PLAN_POSITION_KINEMATIC(); - - /** - * Move the Z probe (or just the nozzle) to the safe homing point - */ - destination[X_AXIS] = round(Z_SAFE_HOMING_X_POINT - (X_PROBE_OFFSET_FROM_EXTRUDER)); - destination[Y_AXIS] = round(Z_SAFE_HOMING_Y_POINT - (Y_PROBE_OFFSET_FROM_EXTRUDER)); - destination[Z_AXIS] = current_position[Z_AXIS]; // Z is already at the right height - - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - DEBUG_POS("> Z_SAFE_HOMING > home_all_axis", current_position); - DEBUG_POS("> Z_SAFE_HOMING > home_all_axis", destination); - } - #endif - - // Move in the XY plane - do_blocking_move_to_xy(destination[X_AXIS], destination[Y_AXIS]); - } - - // Let's see if X and Y are homed - if (axis_unhomed_error(true, true, false)) return; - - /** - * Make sure the Z probe is within the physical limits - * NOTE: This doesn't necessarily ensure the Z probe is also - * within the bed! - */ - float cpx = RAW_CURRENT_POSITION(X_AXIS), cpy = RAW_CURRENT_POSITION(Y_AXIS); - if ( cpx >= X_MIN_POS - (X_PROBE_OFFSET_FROM_EXTRUDER) - && cpx <= X_MAX_POS - (X_PROBE_OFFSET_FROM_EXTRUDER) - && cpy >= Y_MIN_POS - (Y_PROBE_OFFSET_FROM_EXTRUDER) - && cpy <= Y_MAX_POS - (Y_PROBE_OFFSET_FROM_EXTRUDER)) { - - // Home the Z axis - HOMEAXIS(Z); - } - else { - LCD_MESSAGEPGM(MSG_ZPROBE_OUT); - SERIAL_ECHO_START; - SERIAL_ECHOLNPGM(MSG_ZPROBE_OUT); - } - - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - SERIAL_ECHOLNPGM("<<< Z_SAFE_HOMING"); - } - #endif - - #else // !Z_SAFE_HOMING - + home_z_safely(); + #else HOMEAXIS(Z); - - #endif // !Z_SAFE_HOMING - + #endif #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("> (home_all_axis || homeZ) > final", current_position); #endif - } // home_all_axis || homeZ - #endif // Z_HOME_DIR < 0 SYNC_PLAN_POSITION_KINEMATIC(); #endif // !DELTA (gcode_G28) - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> endstops.not_homing()"); - #endif endstops.not_homing(); - endstops.hit_on_purpose(); // clear endstop hit flags + + #if ENABLED(DELTA) && ENABLED(DELTA_HOME_TO_SAFE_ZONE) + // move to a height where we can use the full xy-area + do_blocking_move_to_z(delta_clip_start_height); + #endif // Enable mesh leveling again #if ENABLED(MESH_BED_LEVELING) @@ -3146,19 +3503,13 @@ inline void gcode_G28() { #if ENABLED(MESH_G28_REST_ORIGIN) current_position[Z_AXIS] = 0.0; set_destination_to_current(); - feedrate_mm_m = homing_feedrate_mm_m[Z_AXIS]; - line_to_destination(); + line_to_destination(homing_feedrate_mm_s[Z_AXIS]); stepper.synchronize(); #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("MBL Rest Origin", current_position); #endif #else - current_position[Z_AXIS] = MESH_HOME_SEARCH_Z - - mbl.get_z(RAW_CURRENT_POSITION(X_AXIS), RAW_CURRENT_POSITION(Y_AXIS)) - #if Z_HOME_DIR > 0 - + Z_MAX_POS - #endif - ; + planner.unapply_leveling(current_position); #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("MBL adjusted MESH_HOME_SEARCH_Z", current_position); #endif @@ -3168,8 +3519,7 @@ inline void gcode_G28() { current_position[Z_AXIS] = pre_home_z; SYNC_PLAN_POSITION_KINEMATIC(); mbl.set_active(true); - current_position[Z_AXIS] = pre_home_z - - mbl.get_z(RAW_CURRENT_POSITION(X_AXIS), RAW_CURRENT_POSITION(Y_AXIS)); + planner.unapply_leveling(current_position); #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("MBL Home X or Y", current_position); #endif @@ -3177,11 +3527,6 @@ inline void gcode_G28() { } #endif - #if ENABLED(DELTA) - // move to a height where we can use the full xy-area - do_blocking_move_to_z(delta_clip_start_height); - #endif - clean_up_after_endstop_or_probe_move(); #if ENABLED(DEBUG_LEVELING_FEATURE) @@ -3207,32 +3552,38 @@ inline void gcode_G28() { #endif #if ENABLED(MESH_BED_LEVELING) + inline void _mbl_goto_xy(float x, float y) { - float old_feedrate_mm_m = feedrate_mm_m; - feedrate_mm_m = homing_feedrate_mm_m[X_AXIS]; + float old_feedrate_mm_s = feedrate_mm_s; + feedrate_mm_s = homing_feedrate_mm_s[Z_AXIS]; current_position[Z_AXIS] = MESH_HOME_SEARCH_Z - #if Z_PROBE_TRAVEL_HEIGHT > Z_HOMING_HEIGHT - + Z_PROBE_TRAVEL_HEIGHT + #if Z_CLEARANCE_BETWEEN_PROBES > Z_HOMING_HEIGHT + + Z_CLEARANCE_BETWEEN_PROBES #elif Z_HOMING_HEIGHT > 0 + Z_HOMING_HEIGHT #endif ; line_to_current_position(); + feedrate_mm_s = MMM_TO_MMS(XY_PROBE_SPEED); current_position[X_AXIS] = LOGICAL_X_POSITION(x); current_position[Y_AXIS] = LOGICAL_Y_POSITION(y); line_to_current_position(); - #if Z_PROBE_TRAVEL_HEIGHT > 0 || Z_HOMING_HEIGHT > 0 + #if Z_CLEARANCE_BETWEEN_PROBES > 0 || Z_HOMING_HEIGHT > 0 + feedrate_mm_s = homing_feedrate_mm_s[Z_AXIS]; current_position[Z_AXIS] = LOGICAL_Z_POSITION(MESH_HOME_SEARCH_Z); line_to_current_position(); #endif - feedrate_mm_m = old_feedrate_mm_m; + feedrate_mm_s = old_feedrate_mm_s; stepper.synchronize(); } + // Save 130 bytes with non-duplication of PSTR + void say_not_entered() { SERIAL_PROTOCOLLNPGM(" not entered."); } + /** * G29: Mesh-based Z probe, probes a grid and produces a * mesh to compensate for variable bed height @@ -3268,11 +3619,10 @@ inline void gcode_G28() { switch (state) { case MeshReport: if (mbl.has_mesh()) { - SERIAL_PROTOCOLPAIR("State: ", mbl.active() ? "On" : "Off"); - SERIAL_PROTOCOLPAIR("\nNum X,Y: ", MESH_NUM_X_POINTS); - SERIAL_PROTOCOLCHAR(','); SERIAL_PROTOCOL(MESH_NUM_Y_POINTS); - SERIAL_PROTOCOLPAIR("\nZ search height: ", MESH_HOME_SEARCH_Z); - SERIAL_PROTOCOLPGM("\nZ offset: "); SERIAL_PROTOCOL_F(mbl.z_offset, 5); + SERIAL_PROTOCOLPAIR("State: ", mbl.active() ? MSG_ON : MSG_OFF); + SERIAL_PROTOCOLLNPGM("\nNum X,Y: " STRINGIFY(MESH_NUM_X_POINTS) "," STRINGIFY(MESH_NUM_Y_POINTS)); + SERIAL_PROTOCOLLNPGM("Z search height: " STRINGIFY(MESH_HOME_SEARCH_Z)); + SERIAL_PROTOCOLPGM("Z offset: "); SERIAL_PROTOCOL_F(mbl.z_offset, 5); SERIAL_PROTOCOLLNPGM("\nMeasured points:"); for (py = 0; py < MESH_NUM_Y_POINTS; py++) { for (px = 0; px < MESH_NUM_X_POINTS; px++) { @@ -3320,8 +3670,8 @@ inline void gcode_G28() { else { // One last "return to the bed" (as originally coded) at completion current_position[Z_AXIS] = MESH_HOME_SEARCH_Z - #if Z_PROBE_TRAVEL_HEIGHT > Z_HOMING_HEIGHT - + Z_PROBE_TRAVEL_HEIGHT + #if Z_CLEARANCE_BETWEEN_PROBES > Z_HOMING_HEIGHT + + Z_CLEARANCE_BETWEEN_PROBES #elif Z_HOMING_HEIGHT > 0 + Z_HOMING_HEIGHT #endif @@ -3346,9 +3696,10 @@ inline void gcode_G28() { } } else { - SERIAL_PROTOCOLLNPGM("X not entered."); + SERIAL_CHAR('X'); say_not_entered(); return; } + if (code_seen('Y')) { py = code_value_int() - 1; if (py < 0 || py >= MESH_NUM_Y_POINTS) { @@ -3357,14 +3708,15 @@ inline void gcode_G28() { } } else { - SERIAL_PROTOCOLLNPGM("Y not entered."); + SERIAL_CHAR('Y'); say_not_entered(); return; } + if (code_seen('Z')) { mbl.z_values[py][px] = code_value_axis_units(Z_AXIS); } else { - SERIAL_PROTOCOLLNPGM("Z not entered."); + SERIAL_CHAR('Z'); say_not_entered(); return; } break; @@ -3374,15 +3726,15 @@ inline void gcode_G28() { mbl.z_offset = code_value_axis_units(Z_AXIS); } else { - SERIAL_PROTOCOLLNPGM("Z not entered."); + SERIAL_CHAR('Z'); say_not_entered(); return; } break; case MeshReset: if (mbl.active()) { - current_position[Z_AXIS] += - mbl.get_z(RAW_CURRENT_POSITION(X_AXIS), RAW_CURRENT_POSITION(Y_AXIS)) - MESH_HOME_SEARCH_Z; + current_position[Z_AXIS] -= MESH_HOME_SEARCH_Z; + planner.apply_leveling(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS]); mbl.reset(); SYNC_PLAN_POSITION_KINEMATIC(); } @@ -3394,7 +3746,7 @@ inline void gcode_G28() { report_current_position(); } -#elif ENABLED(AUTO_BED_LEVELING_FEATURE) +#elif HAS_ABL /** * G29: Detailed Z probe, probes the bed at 3 or more points. @@ -3402,7 +3754,7 @@ inline void gcode_G28() { * * Enhanced G29 Auto Bed Leveling Probe Routine * - * Parameters With AUTO_BED_LEVELING_GRID: + * Parameters With ABL_GRID: * * P Set the size of the grid that will be probed (P x P points). * Not supported by non-linear delta printer bed leveling. @@ -3437,10 +3789,15 @@ inline void gcode_G28() { inline void gcode_G29() { #if ENABLED(DEBUG_LEVELING_FEATURE) + bool query = code_seen('Q'); + uint8_t old_debug_flags = marlin_debug_flags; + if (query) marlin_debug_flags |= DEBUG_LEVELING; if (DEBUGGING(LEVELING)) { - SERIAL_ECHOLNPGM(">>> gcode_G29"); - DEBUG_POS("", current_position); + DEBUG_POS(">>> gcode_G29", current_position); + log_machine_info(); } + marlin_debug_flags = old_debug_flags; + if (query) return; #endif // Don't allow auto-leveling without homing first @@ -3448,35 +3805,43 @@ inline void gcode_G28() { int verbose_level = code_seen('V') ? code_value_int() : 1; if (verbose_level < 0 || verbose_level > 4) { - SERIAL_ECHOLNPGM("?(V)erbose Level is implausible (0-4)."); + SERIAL_PROTOCOLLNPGM("?(V)erbose Level is implausible (0-4)."); return; } - bool dryrun = code_seen('D'); - bool stow_probe_after_each = code_seen('E'); + bool dryrun = code_seen('D'), + stow_probe_after_each = code_seen('E'); - #if ENABLED(AUTO_BED_LEVELING_GRID) - - #if DISABLED(DELTA) - bool do_topography_map = verbose_level > 2 || code_seen('T'); - #endif + #if ABL_GRID if (verbose_level > 0) { SERIAL_PROTOCOLLNPGM("G29 Auto Bed Leveling"); if (dryrun) SERIAL_PROTOCOLLNPGM("Running in DRY-RUN mode"); } - int auto_bed_leveling_grid_points = AUTO_BED_LEVELING_GRID_POINTS; + #if ABL_PLANAR - #if DISABLED(DELTA) - if (code_seen('P')) auto_bed_leveling_grid_points = code_value_int(); - if (auto_bed_leveling_grid_points < 2) { - SERIAL_PROTOCOLLNPGM("?Number of probed (P)oints is implausible (2 minimum)."); + bool do_topography_map = verbose_level > 2 || code_seen('T'); + + // X and Y specify points in each direction, overriding the default + // These values may be saved with the completed mesh + int abl_grid_points_x = code_seen('X') ? code_value_int() : ABL_GRID_POINTS_X, + abl_grid_points_y = code_seen('Y') ? code_value_int() : ABL_GRID_POINTS_Y; + + if (code_seen('P')) abl_grid_points_x = abl_grid_points_y = code_value_int(); + + if (abl_grid_points_x < 2 || abl_grid_points_y < 2) { + SERIAL_PROTOCOLLNPGM("?Number of probe points is implausible (2 minimum)."); return; } + + #else + + const int abl_grid_points_x = ABL_GRID_POINTS_X, abl_grid_points_y = ABL_GRID_POINTS_Y; + #endif - xy_probe_feedrate_mm_m = code_seen('S') ? (int)code_value_linear_units() : XY_PROBE_SPEED; + xy_probe_feedrate_mm_s = MMM_TO_MMS(code_seen('S') ? code_value_linear_units() : XY_PROBE_SPEED); int left_probe_bed_position = code_seen('L') ? (int)code_value_axis_units(X_AXIS) : LOGICAL_X_POSITION(LEFT_PROBE_BED_POSITION), right_probe_bed_position = code_seen('R') ? (int)code_value_axis_units(X_AXIS) : LOGICAL_X_POSITION(RIGHT_PROBE_BED_POSITION), @@ -3512,63 +3877,61 @@ inline void gcode_G28() { return; } - #endif // AUTO_BED_LEVELING_GRID - - if (!dryrun) { - - #if ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(DELTA) - if (DEBUGGING(LEVELING)) { - vector_3 corrected_position = planner.adjusted_position(); - DEBUG_POS("BEFORE matrix.set_to_identity", corrected_position); - DEBUG_POS("BEFORE matrix.set_to_identity", current_position); - } - #endif - - // make sure the bed_level_rotation_matrix is identity or the planner will get it wrong - planner.bed_level_matrix.set_to_identity(); - - #if ENABLED(DELTA) - reset_bed_level(); - #else //!DELTA - - //vector_3 corrected_position = planner.adjusted_position(); - //corrected_position.debug("position before G29"); - vector_3 uncorrected_position = planner.adjusted_position(); - //uncorrected_position.debug("position during G29"); - current_position[X_AXIS] = uncorrected_position.x; - current_position[Y_AXIS] = uncorrected_position.y; - current_position[Z_AXIS] = uncorrected_position.z; - - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) DEBUG_POS("AFTER matrix.set_to_identity", uncorrected_position); - #endif - - SYNC_PLAN_POSITION_KINEMATIC(); - - #endif // !DELTA - } + #endif // ABL_GRID stepper.synchronize(); + // Disable auto bed leveling during G29 + bool abl_should_enable = planner.abl_enabled; + + planner.abl_enabled = false; + + if (!dryrun) { + // Re-orient the current position without leveling + // based on where the steppers are positioned. + set_current_from_steppers_for_axis(ALL_AXES); + + // Sync the planner to where the steppers stopped + SYNC_PLAN_POSITION_KINEMATIC(); + } + setup_for_endstop_or_probe_move(); // Deploy the probe. Probe will raise if needed. - if (DEPLOY_PROBE()) return; + if (DEPLOY_PROBE()) { + planner.abl_enabled = abl_should_enable; + return; + } - bed_leveling_in_progress = true; + float xProbe = 0, yProbe = 0, measured_z = 0; - #if ENABLED(AUTO_BED_LEVELING_GRID) + #if ABL_GRID // probe at the points of a lattice grid - const int xGridSpacing = (right_probe_bed_position - left_probe_bed_position) / (auto_bed_leveling_grid_points - 1), - yGridSpacing = (back_probe_bed_position - front_probe_bed_position) / (auto_bed_leveling_grid_points - 1); + const float xGridSpacing = (right_probe_bed_position - left_probe_bed_position) / (abl_grid_points_x - 1), + yGridSpacing = (back_probe_bed_position - front_probe_bed_position) / (abl_grid_points_y - 1); + + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - #if ENABLED(DELTA) - delta_grid_spacing[0] = xGridSpacing; - delta_grid_spacing[1] = yGridSpacing; float zoffset = zprobe_zoffset; if (code_seen('Z')) zoffset += code_value_axis_units(Z_AXIS); - #else // !DELTA + + if ( xGridSpacing != bilinear_grid_spacing[X_AXIS] + || yGridSpacing != bilinear_grid_spacing[Y_AXIS] + || left_probe_bed_position != bilinear_start[X_AXIS] + || front_probe_bed_position != bilinear_start[Y_AXIS] + ) { + reset_bed_level(); + bilinear_grid_spacing[X_AXIS] = xGridSpacing; + bilinear_grid_spacing[Y_AXIS] = yGridSpacing; + bilinear_start[X_AXIS] = RAW_X_POSITION(left_probe_bed_position); + bilinear_start[Y_AXIS] = RAW_Y_POSITION(front_probe_bed_position); + // Can't re-enable (on error) until the new grid is written + abl_should_enable = false; + } + + #elif ENABLED(AUTO_BED_LEVELING_LINEAR) + /** * solve the plane equation ax + by + d = z * A is the matrix with rows [x y 1] for all the probed points @@ -3578,87 +3941,143 @@ inline void gcode_G28() { * so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z */ - int abl2 = sq(auto_bed_leveling_grid_points); + int abl2 = abl_grid_points_x * abl_grid_points_y, + indexIntoAB[abl_grid_points_x][abl_grid_points_y], + probePointCounter = -1; - double eqnAMatrix[abl2 * 3], // "A" matrix of the linear system of equations - eqnBVector[abl2], // "B" vector of Z points - mean = 0.0; - int8_t indexIntoAB[auto_bed_leveling_grid_points][auto_bed_leveling_grid_points]; - #endif // !DELTA + float eqnAMatrix[abl2 * 3], // "A" matrix of the linear system of equations + eqnBVector[abl2], // "B" vector of Z points + mean = 0.0; - int probePointCounter = 0; - bool zig = (auto_bed_leveling_grid_points & 1) ? true : false; //always end at [RIGHT_PROBE_BED_POSITION, BACK_PROBE_BED_POSITION] + #endif // AUTO_BED_LEVELING_LINEAR - for (int yCount = 0; yCount < auto_bed_leveling_grid_points; yCount++) { - double yProbe = front_probe_bed_position + yGridSpacing * yCount; - int xStart, xStop, xInc; + #if ENABLED(PROBE_Y_FIRST) + #define PR_OUTER_VAR xCount + #define PR_OUTER_END abl_grid_points_x + #define PR_INNER_VAR yCount + #define PR_INNER_END abl_grid_points_y + #else + #define PR_OUTER_VAR yCount + #define PR_OUTER_END abl_grid_points_y + #define PR_INNER_VAR xCount + #define PR_INNER_END abl_grid_points_x + #endif - if (zig) { - xStart = 0; - xStop = auto_bed_leveling_grid_points; - xInc = 1; + bool zig = PR_OUTER_END & 1; // Always end at RIGHT and BACK_PROBE_BED_POSITION + + // Outer loop is Y with PROBE_Y_FIRST disabled + for (uint8_t PR_OUTER_VAR = 0; PR_OUTER_VAR < PR_OUTER_END; PR_OUTER_VAR++) { + + int8_t inStart, inStop, inInc; + + if (zig) { // away from origin + inStart = 0; + inStop = PR_INNER_END; + inInc = 1; } - else { - xStart = auto_bed_leveling_grid_points - 1; - xStop = -1; - xInc = -1; + else { // towards origin + inStart = PR_INNER_END - 1; + inStop = -1; + inInc = -1; } - zig = !zig; + zig = !zig; // zag - for (int xCount = xStart; xCount != xStop; xCount += xInc) { - double xProbe = left_probe_bed_position + xGridSpacing * xCount; + // Inner loop is Y with PROBE_Y_FIRST enabled + for (int8_t PR_INNER_VAR = inStart; PR_INNER_VAR != inStop; PR_INNER_VAR += inInc) { - #if ENABLED(DELTA) - // Avoid probing the corners (outside the round or hexagon print surface) on a delta printer. - float distance_from_center = HYPOT(xProbe, yProbe); - if (distance_from_center > DELTA_PROBEABLE_RADIUS) continue; - #endif //DELTA + float xBase = left_probe_bed_position + xGridSpacing * xCount, + yBase = front_probe_bed_position + yGridSpacing * yCount; - float measured_z = probe_pt(xProbe, yProbe, stow_probe_after_each, verbose_level); + xProbe = floor(xBase + (xBase < 0 ? 0 : 0.5)); + yProbe = floor(yBase + (yBase < 0 ? 0 : 0.5)); + + #if ENABLED(AUTO_BED_LEVELING_LINEAR) + indexIntoAB[xCount][yCount] = ++probePointCounter; + #endif + + #if IS_KINEMATIC + // Avoid probing outside the round or hexagonal area + float pos[XYZ] = { xProbe, yProbe, 0 }; + if (!position_is_reachable(pos, true)) continue; + #endif + + measured_z = probe_pt(xProbe, yProbe, stow_probe_after_each, verbose_level); + + if (measured_z == NAN) { + planner.abl_enabled = abl_should_enable; + return; + } + + #if ENABLED(AUTO_BED_LEVELING_LINEAR) - #if DISABLED(DELTA) mean += measured_z; - eqnBVector[probePointCounter] = measured_z; eqnAMatrix[probePointCounter + 0 * abl2] = xProbe; eqnAMatrix[probePointCounter + 1 * abl2] = yProbe; eqnAMatrix[probePointCounter + 2 * abl2] = 1; - indexIntoAB[xCount][yCount] = probePointCounter; - #else - bed_level[xCount][yCount] = measured_z + zoffset; - #endif - probePointCounter++; + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + + bed_level_grid[xCount][yCount] = measured_z + zoffset; + + #endif idle(); } //xProbe } //yProbe - #else // !AUTO_BED_LEVELING_GRID + #elif ENABLED(AUTO_BED_LEVELING_3POINT) #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("> 3-point Leveling"); #endif // Probe at 3 arbitrary points - float z_at_pt_1 = probe_pt( LOGICAL_X_POSITION(ABL_PROBE_PT_1_X), - LOGICAL_Y_POSITION(ABL_PROBE_PT_1_Y), - stow_probe_after_each, verbose_level), - z_at_pt_2 = probe_pt( LOGICAL_X_POSITION(ABL_PROBE_PT_2_X), - LOGICAL_Y_POSITION(ABL_PROBE_PT_2_Y), - stow_probe_after_each, verbose_level), - z_at_pt_3 = probe_pt( LOGICAL_X_POSITION(ABL_PROBE_PT_3_X), - LOGICAL_Y_POSITION(ABL_PROBE_PT_3_Y), - stow_probe_after_each, verbose_level); + vector_3 points[3] = { + vector_3(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, 0), + vector_3(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, 0), + vector_3(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, 0) + }; - if (!dryrun) set_bed_level_equation_3pts(z_at_pt_1, z_at_pt_2, z_at_pt_3); + for (uint8_t i = 0; i < 3; ++i) { + // Retain the last probe position + xProbe = LOGICAL_X_POSITION(points[i].x); + yProbe = LOGICAL_Y_POSITION(points[i].y); + measured_z = points[i].z = probe_pt(xProbe, yProbe, stow_probe_after_each, verbose_level); + } - #endif // !AUTO_BED_LEVELING_GRID + if (measured_z == NAN) { + planner.abl_enabled = abl_should_enable; + return; + } - // Raise to _Z_PROBE_DEPLOY_HEIGHT. Stow the probe. - if (STOW_PROBE()) return; + if (!dryrun) { + vector_3 planeNormal = vector_3::cross(points[0] - points[1], points[2] - points[1]).get_normal(); + if (planeNormal.z < 0) { + planeNormal.x *= -1; + planeNormal.y *= -1; + planeNormal.z *= -1; + } + planner.bed_level_matrix = matrix_3x3::create_look_at(planeNormal); + + // Can't re-enable (on error) until the new grid is written + abl_should_enable = false; + } + + #endif // AUTO_BED_LEVELING_3POINT + + // Raise to _Z_CLEARANCE_DEPLOY_PROBE. Stow the probe. + if (STOW_PROBE()) { + planner.abl_enabled = abl_should_enable; + return; + } + + // + // Unless this is a dry run, auto bed leveling will + // definitely be enabled after this point + // // Restore state after probing clean_up_after_endstop_or_probe_move(); @@ -3668,69 +4087,98 @@ inline void gcode_G28() { #endif // Calculate leveling, print reports, correct the position - #if ENABLED(AUTO_BED_LEVELING_GRID) - #if ENABLED(DELTA) + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (!dryrun) extrapolate_unprobed_bed_level(); - print_bed_level(); + if (!dryrun) extrapolate_unprobed_bed_level(); + print_bed_level(); - #else // !DELTA + #elif ENABLED(AUTO_BED_LEVELING_LINEAR) - // solve lsq problem - double plane_equation_coefficients[3]; - qr_solve(plane_equation_coefficients, abl2, 3, eqnAMatrix, eqnBVector); + // For LINEAR leveling calculate matrix, print reports, correct the position - mean /= abl2; + // solve lsq problem + float plane_equation_coefficients[3]; + qr_solve(plane_equation_coefficients, abl2, 3, eqnAMatrix, eqnBVector); - if (verbose_level) { - SERIAL_PROTOCOLPGM("Eqn coefficients: a: "); - SERIAL_PROTOCOL_F(plane_equation_coefficients[0], 8); - SERIAL_PROTOCOLPGM(" b: "); - SERIAL_PROTOCOL_F(plane_equation_coefficients[1], 8); - SERIAL_PROTOCOLPGM(" d: "); - SERIAL_PROTOCOL_F(plane_equation_coefficients[2], 8); + mean /= abl2; + + if (verbose_level) { + SERIAL_PROTOCOLPGM("Eqn coefficients: a: "); + SERIAL_PROTOCOL_F(plane_equation_coefficients[0], 8); + SERIAL_PROTOCOLPGM(" b: "); + SERIAL_PROTOCOL_F(plane_equation_coefficients[1], 8); + SERIAL_PROTOCOLPGM(" d: "); + SERIAL_PROTOCOL_F(plane_equation_coefficients[2], 8); + SERIAL_EOL; + if (verbose_level > 2) { + SERIAL_PROTOCOLPGM("Mean of sampled points: "); + SERIAL_PROTOCOL_F(mean, 8); SERIAL_EOL; - if (verbose_level > 2) { - SERIAL_PROTOCOLPGM("Mean of sampled points: "); - SERIAL_PROTOCOL_F(mean, 8); - SERIAL_EOL; - } } + } - if (!dryrun) set_bed_level_equation_lsq(plane_equation_coefficients); + // Create the matrix but don't correct the position yet + if (!dryrun) { + planner.bed_level_matrix = matrix_3x3::create_look_at( + vector_3(-plane_equation_coefficients[0], -plane_equation_coefficients[1], 1) + ); + } - // Show the Topography map if enabled - if (do_topography_map) { + // Show the Topography map if enabled + if (do_topography_map) { - SERIAL_PROTOCOLLNPGM("\nBed Height Topography:\n" - " +--- BACK --+\n" - " | |\n" - " L | (+) | R\n" - " E | | I\n" - " F | (-) N (+) | G\n" - " T | | H\n" - " | (-) | T\n" - " | |\n" - " O-- FRONT --+\n" - " (0,0)"); + SERIAL_PROTOCOLLNPGM("\nBed Height Topography:\n" + " +--- BACK --+\n" + " | |\n" + " L | (+) | R\n" + " E | | I\n" + " F | (-) N (+) | G\n" + " T | | H\n" + " | (-) | T\n" + " | |\n" + " O-- FRONT --+\n" + " (0,0)"); - float min_diff = 999; + float min_diff = 999; - for (int yy = auto_bed_leveling_grid_points - 1; yy >= 0; yy--) { - for (int xx = 0; xx < auto_bed_leveling_grid_points; xx++) { + for (int8_t yy = abl_grid_points_y - 1; yy >= 0; yy--) { + for (uint8_t xx = 0; xx < abl_grid_points_x; xx++) { + int ind = indexIntoAB[xx][yy]; + float diff = eqnBVector[ind] - mean, + x_tmp = eqnAMatrix[ind + 0 * abl2], + y_tmp = eqnAMatrix[ind + 1 * abl2], + z_tmp = 0; + + apply_rotation_xyz(planner.bed_level_matrix, x_tmp, y_tmp, z_tmp); + + NOMORE(min_diff, eqnBVector[ind] - z_tmp); + + if (diff >= 0.0) + SERIAL_PROTOCOLPGM(" +"); // Include + for column alignment + else + SERIAL_PROTOCOLCHAR(' '); + SERIAL_PROTOCOL_F(diff, 5); + } // xx + SERIAL_EOL; + } // yy + SERIAL_EOL; + + if (verbose_level > 3) { + SERIAL_PROTOCOLLNPGM("\nCorrected Bed Height vs. Bed Topology:"); + + for (int8_t yy = abl_grid_points_y - 1; yy >= 0; yy--) { + for (uint8_t xx = 0; xx < abl_grid_points_x; xx++) { int ind = indexIntoAB[xx][yy]; - float diff = eqnBVector[ind] - mean; - float x_tmp = eqnAMatrix[ind + 0 * abl2], y_tmp = eqnAMatrix[ind + 1 * abl2], z_tmp = 0; apply_rotation_xyz(planner.bed_level_matrix, x_tmp, y_tmp, z_tmp); - NOMORE(min_diff, eqnBVector[ind] - z_tmp); - + float diff = eqnBVector[ind] - z_tmp - min_diff; if (diff >= 0.0) - SERIAL_PROTOCOLPGM(" +"); // Include + for column alignment + SERIAL_PROTOCOLPGM(" +"); + // Include + for column alignment else SERIAL_PROTOCOLCHAR(' '); SERIAL_PROTOCOL_F(diff, 5); @@ -3738,83 +4186,89 @@ inline void gcode_G28() { SERIAL_EOL; } // yy SERIAL_EOL; - if (verbose_level > 3) { - SERIAL_PROTOCOLLNPGM("\nCorrected Bed Height vs. Bed Topology:"); + } + } //do_topography_map - for (int yy = auto_bed_leveling_grid_points - 1; yy >= 0; yy--) { - for (int xx = 0; xx < auto_bed_leveling_grid_points; xx++) { - int ind = indexIntoAB[xx][yy]; - float x_tmp = eqnAMatrix[ind + 0 * abl2], - y_tmp = eqnAMatrix[ind + 1 * abl2], - z_tmp = 0; + #endif // AUTO_BED_LEVELING_LINEAR - apply_rotation_xyz(planner.bed_level_matrix, x_tmp, y_tmp, z_tmp); + #if ABL_PLANAR - float diff = eqnBVector[ind] - z_tmp - min_diff; - if (diff >= 0.0) - SERIAL_PROTOCOLPGM(" +"); - // Include + for column alignment - else - SERIAL_PROTOCOLCHAR(' '); - SERIAL_PROTOCOL_F(diff, 5); - } // xx - SERIAL_EOL; - } // yy - SERIAL_EOL; - } - } //do_topography_map - #endif //!DELTA - #endif // AUTO_BED_LEVELING_GRID + // For LINEAR and 3POINT leveling correct the current position - #if DISABLED(DELTA) if (verbose_level > 0) planner.bed_level_matrix.debug("\n\nBed Level Correction Matrix:"); if (!dryrun) { - /** - * Correct the Z height difference from Z probe position and nozzle tip position. - * The Z height on homing is measured by Z probe, but the Z probe is quite far - * from the nozzle. When the bed is uneven, this height must be corrected. - */ - float x_tmp = current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER, - y_tmp = current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER, - z_tmp = current_position[Z_AXIS], - stepper_z = stepper.get_axis_position_mm(Z_AXIS); //get the real Z (since planner.adjusted_position is now correcting the plane) + // + // Correct the current XYZ position based on the tilted plane. + // + + // 1. Get the distance from the current position to the reference point. + float x_dist = RAW_CURRENT_POSITION(X_AXIS) - X_TILT_FULCRUM, + y_dist = RAW_CURRENT_POSITION(Y_AXIS) - Y_TILT_FULCRUM, + z_real = current_position[Z_AXIS], + z_zero = 0; #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR("> BEFORE apply_rotation_xyz > stepper_z = ", stepper_z); - SERIAL_ECHOPAIR(" ... z_tmp = ", z_tmp); - SERIAL_EOL; - } + if (DEBUGGING(LEVELING)) DEBUG_POS("G29 uncorrected XYZ", current_position); #endif - // Apply the correction sending the Z probe offset - apply_rotation_xyz(planner.bed_level_matrix, x_tmp, y_tmp, z_tmp); + matrix_3x3 inverse = matrix_3x3::transpose(planner.bed_level_matrix); + + // 2. Apply the inverse matrix to the distance + // from the reference point to X, Y, and zero. + apply_rotation_xyz(inverse, x_dist, y_dist, z_zero); + + // 3. Get the matrix-based corrected Z. + // (Even if not used, get it for comparison.) + float new_z = z_real + z_zero; + + // 4. Use the last measured distance to the bed, if possible + if ( NEAR(current_position[X_AXIS], xProbe - (X_PROBE_OFFSET_FROM_EXTRUDER)) + && NEAR(current_position[Y_AXIS], yProbe - (Y_PROBE_OFFSET_FROM_EXTRUDER)) + ) { + float simple_z = z_real - (measured_z - (-zprobe_zoffset)); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) { + SERIAL_ECHOPAIR("Z from Probe:", simple_z); + SERIAL_ECHOPAIR(" Matrix:", new_z); + SERIAL_ECHOLNPAIR(" Discrepancy:", simple_z - new_z); + } + #endif + new_z = simple_z; + } + + // 5. The rotated XY and corrected Z are now current_position + current_position[X_AXIS] = LOGICAL_X_POSITION(x_dist) + X_TILT_FULCRUM; + current_position[Y_AXIS] = LOGICAL_Y_POSITION(y_dist) + Y_TILT_FULCRUM; + current_position[Z_AXIS] = new_z; #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR("> AFTER apply_rotation_xyz > z_tmp = ", z_tmp); - SERIAL_EOL; - } - #endif - - // Adjust the current Z and send it to the planner. - current_position[Z_AXIS] += z_tmp - stepper_z; - SYNC_PLAN_POSITION_KINEMATIC(); - - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) DEBUG_POS("> corrected Z in G29", current_position); + if (DEBUGGING(LEVELING)) DEBUG_POS("G29 corrected XYZ", current_position); #endif } - #endif // !DELTA + + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + + if (!dryrun) { + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("G29 uncorrected Z:", current_position[Z_AXIS]); + #endif + + // Unapply the offset because it is going to be immediately applied + // and cause compensation movement in Z + current_position[Z_AXIS] -= bilinear_z_offset(current_position); + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR(" corrected Z:", current_position[Z_AXIS]); + #endif + } + + #endif // ABL_PLANAR #ifdef Z_PROBE_END_SCRIPT #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPGM("Z Probe End Script: "); - SERIAL_ECHOLNPGM(Z_PROBE_END_SCRIPT); - } + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("Z Probe End Script: ", Z_PROBE_END_SCRIPT); #endif enqueue_and_echo_commands_P(PSTR(Z_PROBE_END_SCRIPT)); stepper.synchronize(); @@ -3824,36 +4278,53 @@ inline void gcode_G28() { if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< gcode_G29"); #endif - bed_leveling_in_progress = false; - report_current_position(); KEEPALIVE_STATE(IN_HANDLER); + + // Auto Bed Leveling is complete! Enable if possible. + planner.abl_enabled = dryrun ? abl_should_enable : true; + + if (planner.abl_enabled) + SYNC_PLAN_POSITION_KINEMATIC(); } -#endif //AUTO_BED_LEVELING_FEATURE +#endif // HAS_ABL #if HAS_BED_PROBE /** * G30: Do a single Z probe at the current XY + * Usage: + * G30 + * X = Probe X position (default=current probe position) + * Y = Probe Y position (default=current probe position) + * S = Stows the probe if 1 (default=1) */ inline void gcode_G30() { + float X_probe_location = code_seen('X') ? code_value_axis_units(X_AXIS) : current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER, + Y_probe_location = code_seen('Y') ? code_value_axis_units(Y_AXIS) : current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER; + + float pos[XYZ] = { X_probe_location, Y_probe_location, LOGICAL_Z_POSITION(0) }; + if (!position_is_reachable(pos, true)) return; + + bool stow = code_seen('S') ? code_value_bool() : true; + + // Disable leveling so the planner won't mess with us + #if PLANNER_LEVELING + set_bed_leveling_enabled(false); + #endif setup_for_endstop_or_probe_move(); - // TODO: clear the leveling matrix or the planner will be set incorrectly - float measured_z = probe_pt(current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER, - current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER, - true, 1); + float measured_z = probe_pt(X_probe_location, Y_probe_location, stow, 1); SERIAL_PROTOCOLPGM("Bed X: "); - SERIAL_PROTOCOL(current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER + 0.0001); + SERIAL_PROTOCOL(X_probe_location + 0.0001); SERIAL_PROTOCOLPGM(" Y: "); - SERIAL_PROTOCOL(current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER + 0.0001); + SERIAL_PROTOCOL(Y_probe_location + 0.0001); SERIAL_PROTOCOLPGM(" Z: "); - SERIAL_PROTOCOL(measured_z + 0.0001); - SERIAL_EOL; + SERIAL_PROTOCOLLN(measured_z + 0.0001); clean_up_after_endstop_or_probe_move(); @@ -3876,36 +4347,131 @@ inline void gcode_G28() { #endif // HAS_BED_PROBE +#if ENABLED(G38_PROBE_TARGET) + + static bool G38_run_probe() { + + bool G38_pass_fail = false; + + // Get direction of move and retract + float retract_mm[XYZ]; + LOOP_XYZ(i) { + float dist = destination[i] - current_position[i]; + retract_mm[i] = fabs(dist) < G38_MINIMUM_MOVE ? 0 : home_bump_mm((AxisEnum)i) * (dist > 0 ? -1 : 1); + } + + stepper.synchronize(); // wait until the machine is idle + + // Move until destination reached or target hit + endstops.enable(true); + G38_move = true; + G38_endstop_hit = false; + prepare_move_to_destination(); + stepper.synchronize(); + G38_move = false; + + endstops.hit_on_purpose(); + set_current_from_steppers_for_axis(ALL_AXES); + SYNC_PLAN_POSITION_KINEMATIC(); + + // Only do remaining moves if target was hit + if (G38_endstop_hit) { + + G38_pass_fail = true; + + // Move away by the retract distance + set_destination_to_current(); + LOOP_XYZ(i) destination[i] += retract_mm[i]; + endstops.enable(false); + prepare_move_to_destination(); + stepper.synchronize(); + + feedrate_mm_s /= 4; + + // Bump the target more slowly + LOOP_XYZ(i) destination[i] -= retract_mm[i] * 2; + + endstops.enable(true); + G38_move = true; + prepare_move_to_destination(); + stepper.synchronize(); + G38_move = false; + + set_current_from_steppers_for_axis(ALL_AXES); + SYNC_PLAN_POSITION_KINEMATIC(); + } + + endstops.hit_on_purpose(); + endstops.not_homing(); + return G38_pass_fail; + } + + /** + * G38.2 - probe toward workpiece, stop on contact, signal error if failure + * G38.3 - probe toward workpiece, stop on contact + * + * Like G28 except uses Z min endstop for all axes + */ + inline void gcode_G38(bool is_38_2) { + // Get X Y Z E F + gcode_get_destination(); + + setup_for_endstop_or_probe_move(); + + // If any axis has enough movement, do the move + LOOP_XYZ(i) + if (fabs(destination[i] - current_position[i]) >= G38_MINIMUM_MOVE) { + if (!code_seen('F')) feedrate_mm_s = homing_feedrate_mm_s[i]; + // If G38.2 fails throw an error + if (!G38_run_probe() && is_38_2) { + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Failed to reach target"); + } + break; + } + + clean_up_after_endstop_or_probe_move(); + } + +#endif // G38_PROBE_TARGET + /** * G92: Set current position to given X Y Z E */ inline void gcode_G92() { - bool didE = code_seen('E'); + bool didXYZ = false, + didE = code_seen('E'); if (!didE) stepper.synchronize(); - bool didXYZ = false; LOOP_XYZE(i) { if (code_seen(axis_codes[i])) { - float p = current_position[i], - v = code_value_axis_units(i); + #if IS_SCARA + current_position[i] = code_value_axis_units(i); + if (i != E_AXIS) didXYZ = true; + #else + float p = current_position[i], + v = code_value_axis_units(i); - current_position[i] = v; + current_position[i] = v; - if (i != E_AXIS) { - position_shift[i] += v - p; // Offset the coordinate space - update_software_endstops((AxisEnum)i); - didXYZ = true; - } + if (i != E_AXIS) { + didXYZ = true; + position_shift[i] += v - p; // Offset the coordinate space + update_software_endstops((AxisEnum)i); + } + #endif } } if (didXYZ) SYNC_PLAN_POSITION_KINEMATIC(); else if (didE) sync_plan_position_e(); + + report_current_position(); } -#if ENABLED(ULTIPANEL) +#if ENABLED(EMERGENCY_PARSER) || ENABLED(ULTIPANEL) /** * M0: Unconditional stop - Wait for user button press on LCD @@ -3925,38 +4491,52 @@ inline void gcode_G92() { hasS = codenum > 0; } - if (!hasP && !hasS && *args != '\0') - lcd_setstatus(args, true); + #if ENABLED(ULTIPANEL) + + if (!hasP && !hasS && *args != '\0') + lcd_setstatus(args, true); + else { + LCD_MESSAGEPGM(MSG_USERWAIT); + #if ENABLED(LCD_PROGRESS_BAR) && PROGRESS_MSG_EXPIRE > 0 + dontExpireStatus(); + #endif + } + + #else + + if (!hasP && !hasS && *args != '\0') { + SERIAL_ECHO_START; + SERIAL_ECHOLN(args); + } + + #endif + + wait_for_user = true; + KEEPALIVE_STATE(PAUSED_FOR_USER); + + stepper.synchronize(); + refresh_cmd_timeout(); + + if (codenum > 0) { + codenum += previous_cmd_ms; // wait until this time for a click + while (PENDING(millis(), codenum) && wait_for_user) idle(); + } else { - LCD_MESSAGEPGM(MSG_USERWAIT); - #if ENABLED(LCD_PROGRESS_BAR) && PROGRESS_MSG_EXPIRE > 0 - dontExpireStatus(); + #if ENABLED(ULTIPANEL) + if (lcd_detected()) { + while (wait_for_user) idle(); + IS_SD_PRINTING ? LCD_MESSAGEPGM(MSG_RESUMING) : LCD_MESSAGEPGM(WELCOME_MSG); + } + #else + while (wait_for_user) idle(); #endif } - lcd_ignore_click(); - stepper.synchronize(); - refresh_cmd_timeout(); - if (codenum > 0) { - codenum += previous_cmd_ms; // wait until this time for a click - KEEPALIVE_STATE(PAUSED_FOR_USER); - while (PENDING(millis(), codenum) && !lcd_clicked()) idle(); - KEEPALIVE_STATE(IN_HANDLER); - lcd_ignore_click(false); - } - else { - if (!lcd_detected()) return; - KEEPALIVE_STATE(PAUSED_FOR_USER); - while (!lcd_clicked()) idle(); - KEEPALIVE_STATE(IN_HANDLER); - } - if (IS_SD_PRINTING) - LCD_MESSAGEPGM(MSG_RESUMING); - else - LCD_MESSAGEPGM(WELCOME_MSG); + wait_for_user = false; + KEEPALIVE_STATE(IN_HANDLER); } -#endif // ULTIPANEL +#endif // EMERGENCY_PARSER || ULTIPANEL /** * M17: Enable power on all stepper motors @@ -3980,23 +4560,17 @@ inline void gcode_M17() { /** * M21: Init SD Card */ - inline void gcode_M21() { - card.initsd(); - } + inline void gcode_M21() { card.initsd(); } /** * M22: Release SD Card */ - inline void gcode_M22() { - card.release(); - } + inline void gcode_M22() { card.release(); } /** * M23: Open a file */ - inline void gcode_M23() { - card.openFile(current_command_args, true); - } + inline void gcode_M23() { card.openFile(current_command_args, true); } /** * M24: Start SD Print @@ -4009,9 +4583,7 @@ inline void gcode_M17() { /** * M25: Pause SD Print */ - inline void gcode_M25() { - card.pauseSDPrint(); - } + inline void gcode_M25() { card.pauseSDPrint(); } /** * M26: Set SD Card file index @@ -4024,16 +4596,12 @@ inline void gcode_M17() { /** * M27: Get SD Card status */ - inline void gcode_M27() { - card.getStatus(); - } + inline void gcode_M27() { card.getStatus(); } /** * M28: Start SD Write */ - inline void gcode_M28() { - card.openFile(current_command_args, false); - } + inline void gcode_M28() { card.openFile(current_command_args, false); } /** * M29: Stop SD Write @@ -4053,7 +4621,7 @@ inline void gcode_M17() { } } -#endif //SDSUPPORT +#endif // SDSUPPORT /** * M31: Get the time since the start of SD Print (or last M109) @@ -4066,10 +4634,11 @@ inline void gcode_M31() { lcd_setstatus(buffer); SERIAL_ECHO_START; - SERIAL_ECHOPGM("Print time: "); - SERIAL_ECHOLN(buffer); + SERIAL_ECHOLNPAIR("Print time: ", buffer); - thermalManager.autotempShutdown(); + #if ENABLED(AUTOTEMP) + thermalManager.autotempShutdown(); + #endif } #if ENABLED(SDSUPPORT) @@ -4131,6 +4700,16 @@ inline void gcode_M31() { #endif // SDSUPPORT +/** + * Sensitive pin test for M42, M226 + */ +static bool pin_is_protected(uint8_t pin) { + static const int sensitive_pins[] = SENSITIVE_PINS; + for (uint8_t i = 0; i < COUNT(sensitive_pins); i++) + if (sensitive_pins[i] == pin) return true; + return false; +} + /** * M42: Change pin status via GCode * @@ -4146,8 +4725,11 @@ inline void gcode_M42() { int pin_number = code_seen('P') ? code_value_int() : LED_PIN; if (pin_number < 0) return; - for (uint8_t i = 0; i < COUNT(sensitive_pins); i++) - if (pin_number == sensitive_pins[i]) return; + if (pin_is_protected(pin_number)) { + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM(MSG_ERR_PROTECTED_PIN); + return; + } pinMode(pin_number, OUTPUT); digitalWrite(pin_number, pin_status); @@ -4168,6 +4750,91 @@ inline void gcode_M42() { #endif } +#if ENABLED(PINS_DEBUGGING) + + #include "pinsDebug.h" + + /** + * M43: Pin report and debug + * + * E Enable / disable background endstop monitoring + * - Machine continues to operate + * - Reports changes to endstops + * - Toggles LED when an endstop changes + * + * or + * + * P Pin to read or watch. If omitted, read/watch all pins. + * W Watch pins -reporting changes- until reset, click, or M108. + * I Flag to ignore Marlin's pin protection. + * + */ + inline void gcode_M43() { + + // Enable or disable endstop monitoring + if (code_seen('E')) { + endstop_monitor_flag = code_value_bool(); + SERIAL_PROTOCOLPGM("endstop monitor "); + SERIAL_PROTOCOL(endstop_monitor_flag ? "en" : "dis"); + SERIAL_PROTOCOLLNPGM("abled"); + return; + } + + // Get the range of pins to test or watch + int first_pin = 0, last_pin = NUM_DIGITAL_PINS - 1; + if (code_seen('P')) { + first_pin = last_pin = code_value_byte(); + if (first_pin > NUM_DIGITAL_PINS - 1) return; + } + + bool ignore_protection = code_seen('I') ? code_value_bool() : false; + + // Watch until click, M108, or reset + if (code_seen('W') && code_value_bool()) { // watch digital pins + byte pin_state[last_pin - first_pin + 1]; + for (int8_t pin = first_pin; pin <= last_pin; pin++) { + if (pin_is_protected(pin) && !ignore_protection) continue; + pinMode(pin, INPUT_PULLUP); + // if (IS_ANALOG(pin)) + // pin_state[pin - first_pin] = analogRead(pin - analogInputToDigitalPin(0)); // int16_t pin_state[...] + // else + pin_state[pin - first_pin] = digitalRead(pin); + } + + #if ENABLED(EMERGENCY_PARSER) || ENABLED(ULTIPANEL) + wait_for_user = true; + #endif + + for(;;) { + for (int8_t pin = first_pin; pin <= last_pin; pin++) { + if (pin_is_protected(pin)) continue; + byte val; + // if (IS_ANALOG(pin)) + // val = analogRead(pin - analogInputToDigitalPin(0)); // int16_t val + // else + val = digitalRead(pin); + if (val != pin_state[pin - first_pin]) { + report_pin_state(pin); + pin_state[pin - first_pin] = val; + } + } + + #if ENABLED(EMERGENCY_PARSER) || ENABLED(ULTIPANEL) + if (!wait_for_user) break; + #endif + + safe_delay(500); + } + return; + } + + // Report current state of selected pin(s) + for (uint8_t pin = first_pin; pin <= last_pin; pin++) + report_pin_state_extended(pin, ignore_protection); + } + +#endif // PINS_DEBUGGING + #if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) /** @@ -4199,7 +4866,7 @@ inline void gcode_M42() { } if (verbose_level > 0) - SERIAL_PROTOCOLLNPGM("M48 Z-Probe Repeatability test"); + SERIAL_PROTOCOLLNPGM("M48 Z-Probe Repeatability Test"); int8_t n_samples = code_seen('P') ? code_value_byte() : 10; if (n_samples < 4 || n_samples > 50) { @@ -4227,7 +4894,8 @@ inline void gcode_M42() { return; } #else - if (HYPOT(RAW_X_POSITION(X_probe_location), RAW_Y_POSITION(Y_probe_location)) > DELTA_PROBEABLE_RADIUS) { + float pos[XYZ] = { X_probe_location, Y_probe_location, 0 }; + if (!position_is_reachable(pos, true)) { SERIAL_PROTOCOLLNPGM("? (X,Y) location outside of probeable radius."); return; } @@ -4252,12 +4920,9 @@ inline void gcode_M42() { if (verbose_level > 2) SERIAL_PROTOCOLLNPGM("Positioning the probe..."); - #if ENABLED(DELTA) - // we don't do bed level correction in M48 because we want the raw data when we probe + // Disable bed level correction in M48 because we want the raw data when we probe + #if HAS_ABL reset_bed_level(); - #elif ENABLED(AUTO_BED_LEVELING_FEATURE) - // we don't do bed level correction in M48 because we want the raw data when we probe - planner.bed_level_matrix.set_to_identity(); #endif setup_for_endstop_or_probe_move(); @@ -4267,7 +4932,8 @@ inline void gcode_M42() { randomSeed(millis()); - double mean = 0, sigma = 0, sample_set[n_samples]; + double mean = 0.0, sigma = 0.0, min = 99999.9, max = -99999.9, sample_set[n_samples]; + for (uint8_t n = 0; n < n_samples; n++) { if (n_legs) { int dir = (random(0, 10) > 5.0) ? -1 : 1; // clockwise or counter clockwise @@ -4322,8 +4988,7 @@ inline void gcode_M42() { Y_current /= 1.25; if (verbose_level > 3) { SERIAL_ECHOPAIR("Pulling point towards center:", X_current); - SERIAL_ECHOPAIR(", ", Y_current); - SERIAL_EOL; + SERIAL_ECHOLNPAIR(", ", Y_current); } } #endif @@ -4331,15 +4996,14 @@ inline void gcode_M42() { SERIAL_PROTOCOLPGM("Going to:"); SERIAL_ECHOPAIR(" X", X_current); SERIAL_ECHOPAIR(" Y", Y_current); - SERIAL_ECHOPAIR(" Z", current_position[Z_AXIS]); - SERIAL_EOL; + SERIAL_ECHOLNPAIR(" Z", current_position[Z_AXIS]); } do_blocking_move_to_xy(X_current, Y_current); } // n_legs loop } // n_legs // Probe a single point - sample_set[n] = probe_pt(X_probe_location, Y_probe_location, stow_probe_after_each, verbose_level); + sample_set[n] = probe_pt(X_probe_location, Y_probe_location, stow_probe_after_each, 0); /** * Get the current mean for the data points we have so far @@ -4348,6 +5012,9 @@ inline void gcode_M42() { for (uint8_t j = 0; j <= n; j++) sum += sample_set[j]; mean = sum / (n + 1); + NOMORE(min, sample_set[n]); + NOLESS(max, sample_set[n]); + /** * Now, use that mean to calculate the standard deviation for the * data points we have so far @@ -4362,13 +5029,19 @@ inline void gcode_M42() { SERIAL_PROTOCOL(n + 1); SERIAL_PROTOCOLPGM(" of "); SERIAL_PROTOCOL((int)n_samples); - SERIAL_PROTOCOLPGM(" z: "); - SERIAL_PROTOCOL_F(current_position[Z_AXIS], 6); + SERIAL_PROTOCOLPGM(": z: "); + SERIAL_PROTOCOL_F(sample_set[n], 3); if (verbose_level > 2) { SERIAL_PROTOCOLPGM(" mean: "); - SERIAL_PROTOCOL_F(mean, 6); - SERIAL_PROTOCOLPGM(" sigma: "); + SERIAL_PROTOCOL_F(mean, 4); + SERIAL_PROTOCOLPGM(" sigma: "); SERIAL_PROTOCOL_F(sigma, 6); + SERIAL_PROTOCOLPGM(" min: "); + SERIAL_PROTOCOL_F(min, 3); + SERIAL_PROTOCOLPGM(" max: "); + SERIAL_PROTOCOL_F(max, 3); + SERIAL_PROTOCOLPGM(" range: "); + SERIAL_PROTOCOL_F(max-min, 3); } } SERIAL_EOL; @@ -4378,15 +5051,25 @@ inline void gcode_M42() { if (STOW_PROBE()) return; + SERIAL_PROTOCOLPGM("Finished!"); + SERIAL_EOL; + if (verbose_level > 0) { SERIAL_PROTOCOLPGM("Mean: "); SERIAL_PROTOCOL_F(mean, 6); + SERIAL_PROTOCOLPGM(" Min: "); + SERIAL_PROTOCOL_F(min, 3); + SERIAL_PROTOCOLPGM(" Max: "); + SERIAL_PROTOCOL_F(max, 3); + SERIAL_PROTOCOLPGM(" Range: "); + SERIAL_PROTOCOL_F(max-min, 3); SERIAL_EOL; } SERIAL_PROTOCOLPGM("Standard Deviation: "); SERIAL_PROTOCOL_F(sigma, 6); - SERIAL_EOL; SERIAL_EOL; + SERIAL_EOL; + SERIAL_EOL; clean_up_after_endstop_or_probe_move(); @@ -4418,7 +5101,8 @@ inline void gcode_M77() { print_job_timer.stop(); } // "M78 S78" will reset the statistics if (code_seen('S') && code_value_int() == 78) print_job_timer.initStats(); - else print_job_timer.showStats(); + else + print_job_timer.showStats(); } #endif @@ -4456,6 +5140,10 @@ inline void gcode_M104() { if (code_value_temp_abs() > thermalManager.degHotend(target_extruder)) LCD_MESSAGEPGM(MSG_HEATING); } + + #if ENABLED(AUTOTEMP) + planner.autotemp_M104_M109(); + #endif } #if HAS_TEMP_HOTEND || HAS_TEMP_BED @@ -4527,6 +5215,32 @@ inline void gcode_M105() { SERIAL_EOL; } +#if ENABLED(AUTO_REPORT_TEMPERATURES) && (HAS_TEMP_HOTEND || HAS_TEMP_BED) + + static uint8_t auto_report_temp_interval; + static millis_t next_temp_report_ms; + + /** + * M155: Set temperature auto-report interval. M155 S + */ + inline void gcode_M155() { + if (code_seen('S')) { + auto_report_temp_interval = code_value_byte(); + NOMORE(auto_report_temp_interval, 60); + next_temp_report_ms = millis() + 1000UL * auto_report_temp_interval; + } + } + + inline void auto_report_temperatures() { + if (auto_report_temp_interval && ELAPSED(millis(), next_temp_report_ms)) { + next_temp_report_ms = millis() + 1000UL * auto_report_temp_interval; + print_heaterstates(); + SERIAL_EOL; + } + } + +#endif // AUTO_REPORT_TEMPERATURES + #if FAN_COUNT > 0 /** @@ -4626,7 +5340,7 @@ inline void gcode_M109() { } #if ENABLED(AUTOTEMP) - planner.autotemp_M109(); + planner.autotemp_M104_M109(); #endif #if TEMP_RESIDENCY_TIME > 0 @@ -4706,7 +5420,8 @@ inline void gcode_M109() { } while (wait_for_heatup && TEMP_CONDITIONS); - LCD_MESSAGEPGM(MSG_HEATING_COMPLETE); + if (wait_for_heatup) LCD_MESSAGEPGM(MSG_HEATING_COMPLETE); + KEEPALIVE_STATE(IN_HANDLER); } @@ -4824,7 +5539,7 @@ inline void gcode_M109() { } while (wait_for_heatup && TEMP_BED_CONDITIONS); - LCD_MESSAGEPGM(MSG_BED_DONE); + if (wait_for_heatup) LCD_MESSAGEPGM(MSG_BED_DONE); KEEPALIVE_STATE(IN_HANDLER); } @@ -4890,8 +5605,7 @@ inline void gcode_M111() { } else { SERIAL_ECHO_START; - SERIAL_ECHOPAIR("M113 S", (unsigned long)host_keepalive_interval); - SERIAL_EOL; + SERIAL_ECHOLNPAIR("M113 S", (unsigned long)host_keepalive_interval); } } @@ -4941,64 +5655,40 @@ inline void gcode_M140() { * F */ inline void gcode_M145() { - int8_t material = code_seen('S') ? (int8_t)code_value_int() : 0; - if (material < 0 || material > 1) { + uint8_t material = code_seen('S') ? (uint8_t)code_value_int() : 0; + if (material >= COUNT(lcd_preheat_hotend_temp)) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_MATERIAL_INDEX); } else { int v; - switch (material) { - case 0: - if (code_seen('H')) { - v = code_value_int(); - preheatHotendTemp1 = constrain(v, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - 15); - } - if (code_seen('F')) { - v = code_value_int(); - preheatFanSpeed1 = constrain(v, 0, 255); - } - #if TEMP_SENSOR_BED != 0 - if (code_seen('B')) { - v = code_value_int(); - preheatBedTemp1 = constrain(v, BED_MINTEMP, BED_MAXTEMP - 15); - } - #endif - break; - case 1: - if (code_seen('H')) { - v = code_value_int(); - preheatHotendTemp2 = constrain(v, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - 15); - } - if (code_seen('F')) { - v = code_value_int(); - preheatFanSpeed2 = constrain(v, 0, 255); - } - #if TEMP_SENSOR_BED != 0 - if (code_seen('B')) { - v = code_value_int(); - preheatBedTemp2 = constrain(v, BED_MINTEMP, BED_MAXTEMP - 15); - } - #endif - break; + if (code_seen('H')) { + v = code_value_int(); + lcd_preheat_hotend_temp[material] = constrain(v, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - 15); } + if (code_seen('F')) { + v = code_value_int(); + lcd_preheat_fan_speed[material] = constrain(v, 0, 255); + } + #if TEMP_SENSOR_BED != 0 + if (code_seen('B')) { + v = code_value_int(); + lcd_preheat_bed_temp[material] = constrain(v, BED_MINTEMP, BED_MAXTEMP - 15); + } + #endif } } -#endif +#endif // ULTIPANEL #if ENABLED(TEMPERATURE_UNITS_SUPPORT) /** * M149: Set temperature units */ inline void gcode_M149() { - if (code_seen('C')) { - set_input_temp_units(TEMPUNIT_C); - } else if (code_seen('K')) { - set_input_temp_units(TEMPUNIT_K); - } else if (code_seen('F')) { - set_input_temp_units(TEMPUNIT_F); - } + if (code_seen('C')) set_input_temp_units(TEMPUNIT_C); + else if (code_seen('K')) set_input_temp_units(TEMPUNIT_K); + else if (code_seen('F')) set_input_temp_units(TEMPUNIT_F); } #endif @@ -5059,7 +5749,6 @@ inline void gcode_M81() { #endif } - /** * M82: Set E codes absolute (default) */ @@ -5106,22 +5795,38 @@ inline void gcode_M85() { if (code_seen('S')) max_inactive_time = code_value_millis_from_seconds(); } +/** + * Multi-stepper support for M92, M201, M203 + */ +#if ENABLED(DISTINCT_E_FACTORS) + #define GET_TARGET_EXTRUDER(CMD) if (get_target_extruder_from_command(CMD)) return + #define TARGET_EXTRUDER target_extruder +#else + #define GET_TARGET_EXTRUDER(CMD) NOOP + #define TARGET_EXTRUDER 0 +#endif + /** * M92: Set axis steps-per-unit for one or more axes, X, Y, Z, and E. * (Follows the same syntax as G92) + * + * With multiple extruders use T to specify which one. */ inline void gcode_M92() { + + GET_TARGET_EXTRUDER(92); + LOOP_XYZE(i) { if (code_seen(axis_codes[i])) { if (i == E_AXIS) { - float value = code_value_per_axis_unit(i); + float value = code_value_per_axis_unit(E_AXIS + TARGET_EXTRUDER); if (value < 20.0) { - float factor = planner.axis_steps_per_mm[i] / value; // increase e constants if M92 E14 is given for netfab. - planner.max_e_jerk *= factor; - planner.max_feedrate_mm_s[i] *= factor; - planner.max_acceleration_steps_per_s2[i] *= factor; + float factor = planner.axis_steps_per_mm[E_AXIS + TARGET_EXTRUDER] / value; // increase e constants if M92 E14 is given for netfab. + planner.max_jerk[E_AXIS] *= factor; + planner.max_feedrate_mm_s[E_AXIS + TARGET_EXTRUDER] *= factor; + planner.max_acceleration_steps_per_s2[E_AXIS + TARGET_EXTRUDER] *= factor; } - planner.axis_steps_per_mm[i] = value; + planner.axis_steps_per_mm[E_AXIS + TARGET_EXTRUDER] = value; } else { planner.axis_steps_per_mm[i] = code_value_per_axis_unit(i); @@ -5146,24 +5851,10 @@ static void report_current_position() { stepper.report_positions(); - #if ENABLED(SCARA) - SERIAL_PROTOCOLPGM("SCARA Theta:"); - SERIAL_PROTOCOL(delta[X_AXIS]); - SERIAL_PROTOCOLPGM(" Psi+Theta:"); - SERIAL_PROTOCOL(delta[Y_AXIS]); + #if IS_SCARA + SERIAL_PROTOCOLPAIR("SCARA Theta:", stepper.get_axis_position_degrees(A_AXIS)); + SERIAL_PROTOCOLLNPAIR(" Psi+Theta:", stepper.get_axis_position_degrees(B_AXIS)); SERIAL_EOL; - - SERIAL_PROTOCOLPGM("SCARA Cal - Theta:"); - SERIAL_PROTOCOL(delta[X_AXIS]); - SERIAL_PROTOCOLPGM(" Psi+Theta (90):"); - SERIAL_PROTOCOL(delta[Y_AXIS] - delta[X_AXIS] - 90); - SERIAL_EOL; - - SERIAL_PROTOCOLPGM("SCARA step Cal - Theta:"); - SERIAL_PROTOCOL(delta[X_AXIS] / 90 * planner.axis_steps_per_mm[X_AXIS]); - SERIAL_PROTOCOLPGM(" Psi+Theta:"); - SERIAL_PROTOCOL((delta[Y_AXIS] - delta[X_AXIS]) / 90 * planner.axis_steps_per_mm[Y_AXIS]); - SERIAL_EOL; SERIAL_EOL; #endif } @@ -5176,7 +5867,63 @@ inline void gcode_M114() { report_current_position(); } * M115: Capabilities string */ inline void gcode_M115() { - SERIAL_PROTOCOLPGM(MSG_M115_REPORT); + SERIAL_PROTOCOLLNPGM(MSG_M115_REPORT); + + #if ENABLED(EXTENDED_CAPABILITIES_REPORT) + + // EEPROM (M500, M501) + #if ENABLED(EEPROM_SETTINGS) + SERIAL_PROTOCOLLNPGM("Cap:EEPROM:1"); + #else + SERIAL_PROTOCOLLNPGM("Cap:EEPROM:0"); + #endif + + // AUTOREPORT_TEMP (M155) + #if ENABLED(AUTO_REPORT_TEMPERATURES) + SERIAL_PROTOCOLLNPGM("Cap:AUTOREPORT_TEMP:1"); + #else + SERIAL_PROTOCOLLNPGM("Cap:AUTOREPORT_TEMP:0"); + #endif + + // PROGRESS (M530 S L, M531 , M532 X L) + SERIAL_PROTOCOLLNPGM("Cap:PROGRESS:0"); + + // AUTOLEVEL (G29) + #if HAS_ABL + SERIAL_PROTOCOLLNPGM("Cap:AUTOLEVEL:1"); + #else + SERIAL_PROTOCOLLNPGM("Cap:AUTOLEVEL:0"); + #endif + + // Z_PROBE (G30) + #if HAS_BED_PROBE + SERIAL_PROTOCOLLNPGM("Cap:Z_PROBE:1"); + #else + SERIAL_PROTOCOLLNPGM("Cap:Z_PROBE:0"); + #endif + + // SOFTWARE_POWER (G30) + #if HAS_POWER_SWITCH + SERIAL_PROTOCOLLNPGM("Cap:SOFTWARE_POWER:1"); + #else + SERIAL_PROTOCOLLNPGM("Cap:SOFTWARE_POWER:0"); + #endif + + // TOGGLE_LIGHTS (M355) + #if HAS_CASE_LIGHT + SERIAL_PROTOCOLLNPGM("Cap:TOGGLE_LIGHTS:1"); + #else + SERIAL_PROTOCOLLNPGM("Cap:TOGGLE_LIGHTS:0"); + #endif + + // EMERGENCY_PARSER (M108, M112, M410) + #if ENABLED(EMERGENCY_PARSER) + SERIAL_PROTOCOLLNPGM("Cap:EMERGENCY_PARSER:1"); + #else + SERIAL_PROTOCOLLNPGM("Cap:EMERGENCY_PARSER:0"); + #endif + + #endif // EXTENDED_CAPABILITIES_REPORT } /** @@ -5201,75 +5948,103 @@ inline void gcode_M120() { endstops.enable_globally(true); } */ inline void gcode_M121() { endstops.enable_globally(false); } -#if ENABLED(BLINKM) +#if ENABLED(HAVE_TMC2130DRIVER) + + /** + * M122: Output Trinamic TMC2130 status to serial output. Very bad formatting. + */ + + static void tmc2130_report(Trinamic_TMC2130 &stepr, const char *name) { + stepr.read_STAT(); + SERIAL_PROTOCOL(name); + SERIAL_PROTOCOL(": "); + stepr.isReset() ? SERIAL_PROTOCOLPGM("RESET ") : SERIAL_PROTOCOLPGM("----- "); + stepr.isError() ? SERIAL_PROTOCOLPGM("ERROR ") : SERIAL_PROTOCOLPGM("----- "); + stepr.isStallguard() ? SERIAL_PROTOCOLPGM("SLGRD ") : SERIAL_PROTOCOLPGM("----- "); + stepr.isStandstill() ? SERIAL_PROTOCOLPGM("STILL ") : SERIAL_PROTOCOLPGM("----- "); + SERIAL_PROTOCOLLN(stepr.debug()); + } + + inline void gcode_M122() { + SERIAL_PROTOCOLLNPGM("Reporting TMC2130 status"); + #if ENABLED(X_IS_TMC2130) + tmc2130_report(stepperX, "X"); + #endif + #if ENABLED(X2_IS_TMC2130) + tmc2130_report(stepperX2, "X2"); + #endif + #if ENABLED(Y_IS_TMC2130) + tmc2130_report(stepperY, "Y"); + #endif + #if ENABLED(Y2_IS_TMC2130) + tmc2130_report(stepperY2, "Y2"); + #endif + #if ENABLED(Z_IS_TMC2130) + tmc2130_report(stepperZ, "Z"); + #endif + #if ENABLED(Z2_IS_TMC2130) + tmc2130_report(stepperZ2, "Z2"); + #endif + #if ENABLED(E0_IS_TMC2130) + tmc2130_report(stepperE0, "E0"); + #endif + #if ENABLED(E1_IS_TMC2130) + tmc2130_report(stepperE1, "E1"); + #endif + #if ENABLED(E2_IS_TMC2130) + tmc2130_report(stepperE2, "E2"); + #endif + #if ENABLED(E3_IS_TMC2130) + tmc2130_report(stepperE3, "E3"); + #endif + } +#endif // HAVE_TMC2130DRIVER + +#if ENABLED(BLINKM) || ENABLED(RGB_LED) + + void set_led_color(const uint8_t r, const uint8_t g, const uint8_t b) { + + #if ENABLED(BLINKM) + + // This variant uses i2c to send the RGB components to the device. + SendColors(r, g, b); + + #else + + // This variant uses 3 separate pins for the RGB components. + // If the pins can do PWM then their intensity will be set. + digitalWrite(RGB_LED_R_PIN, r ? HIGH : LOW); + digitalWrite(RGB_LED_G_PIN, g ? HIGH : LOW); + digitalWrite(RGB_LED_B_PIN, b ? HIGH : LOW); + analogWrite(RGB_LED_R_PIN, r); + analogWrite(RGB_LED_G_PIN, g); + analogWrite(RGB_LED_B_PIN, b); + + #endif + } /** * M150: Set Status LED Color - Use R-U-B for R-G-B + * + * Always sets all 3 components. If a component is left out, set to 0. + * + * Examples: + * + * M150 R255 ; Turn LED red + * M150 R255 U127 ; Turn LED orange (PWM only) + * M150 ; Turn LED off + * M150 R U B ; Turn LED white + * */ inline void gcode_M150() { - SendColors( - code_seen('R') ? code_value_byte() : 0, - code_seen('U') ? code_value_byte() : 0, - code_seen('B') ? code_value_byte() : 0 + set_led_color( + code_seen('R') ? (code_has_value() ? code_value_byte() : 255) : 0, + code_seen('U') ? (code_has_value() ? code_value_byte() : 255) : 0, + code_seen('B') ? (code_has_value() ? code_value_byte() : 255) : 0 ); } -#endif // BLINKM - -#if ENABLED(EXPERIMENTAL_I2CBUS) - - /** - * M155: Send data to a I2C slave device - * - * This is a PoC, the formating and arguments for the GCODE will - * change to be more compatible, the current proposal is: - * - * M155 A ; Sets the I2C slave address the data will be sent to - * - * M155 B - * M155 B - * M155 B - * - * M155 S1 ; Send the buffered data and reset the buffer - * M155 R1 ; Reset the buffer without sending data - * - */ - inline void gcode_M155() { - // Set the target address - if (code_seen('A')) - i2c.address(code_value_byte()); - - // Add a new byte to the buffer - else if (code_seen('B')) - i2c.addbyte(code_value_int()); - - // Flush the buffer to the bus - else if (code_seen('S')) i2c.send(); - - // Reset and rewind the buffer - else if (code_seen('R')) i2c.reset(); - } - - /** - * M156: Request X bytes from I2C slave device - * - * Usage: M156 A B - */ - inline void gcode_M156() { - uint8_t addr = code_seen('A') ? code_value_byte() : 0; - int bytes = code_seen('B') ? code_value_int() : 1; - - if (addr && bytes > 0 && bytes <= 32) { - i2c.address(addr); - i2c.reqbytes(bytes); - } - else { - SERIAL_ERROR_START; - SERIAL_ERRORLN("Bad i2c request"); - } - } - -#endif //EXPERIMENTAL_I2CBUS +#endif // BLINKM || RGB_LED /** * M200: Set filament diameter and set E axis units to cubic units @@ -5302,11 +6077,17 @@ inline void gcode_M200() { /** * M201: Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000) + * + * With multiple extruders use T to specify which one. */ inline void gcode_M201() { + + GET_TARGET_EXTRUDER(201); + LOOP_XYZE(i) { if (code_seen(axis_codes[i])) { - planner.max_acceleration_mm_per_s2[i] = code_value_axis_units(i); + const uint8_t a = i + (i == E_AXIS ? TARGET_EXTRUDER : 0); + planner.max_acceleration_mm_per_s2[a] = code_value_axis_units(a); } } // steps per sq second need to be updated to agree with the units per sq second (as they are what is used in the planner) @@ -5324,11 +6105,18 @@ inline void gcode_M201() { /** * M203: Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in units/sec + * + * With multiple extruders use T to specify which one. */ inline void gcode_M203() { + + GET_TARGET_EXTRUDER(203); + LOOP_XYZE(i) - if (code_seen(axis_codes[i])) - planner.max_feedrate_mm_s[i] = code_value_axis_units(i); + if (code_seen(axis_codes[i])) { + const uint8_t a = i + (i == E_AXIS ? TARGET_EXTRUDER : 0); + planner.max_feedrate_mm_s[a] = code_value_axis_units(a); + } } /** @@ -5343,23 +6131,19 @@ inline void gcode_M203() { inline void gcode_M204() { if (code_seen('S')) { // Kept for legacy compatibility. Should NOT BE USED for new developments. planner.travel_acceleration = planner.acceleration = code_value_linear_units(); - SERIAL_ECHOPAIR("Setting Print and Travel Acceleration: ", planner.acceleration); - SERIAL_EOL; + SERIAL_ECHOLNPAIR("Setting Print and Travel Acceleration: ", planner.acceleration); } if (code_seen('P')) { planner.acceleration = code_value_linear_units(); - SERIAL_ECHOPAIR("Setting Print Acceleration: ", planner.acceleration); - SERIAL_EOL; + SERIAL_ECHOLNPAIR("Setting Print Acceleration: ", planner.acceleration); } if (code_seen('R')) { planner.retract_acceleration = code_value_linear_units(); - SERIAL_ECHOPAIR("Setting Retract Acceleration: ", planner.retract_acceleration); - SERIAL_EOL; + SERIAL_ECHOLNPAIR("Setting Retract Acceleration: ", planner.retract_acceleration); } if (code_seen('T')) { planner.travel_acceleration = code_value_linear_units(); - SERIAL_ECHOPAIR("Setting Travel Acceleration: ", planner.travel_acceleration); - SERIAL_EOL; + SERIAL_ECHOLNPAIR("Setting Travel Acceleration: ", planner.travel_acceleration); } } @@ -5369,7 +6153,8 @@ inline void gcode_M204() { * S = Min Feed Rate (units/s) * T = Min Travel Feed Rate (units/s) * B = Min Segment Time (µs) - * X = Max XY Jerk (units/sec^2) + * X = Max X Jerk (units/sec^2) + * Y = Max Y Jerk (units/sec^2) * Z = Max Z Jerk (units/sec^2) * E = Max E Jerk (units/sec^2) */ @@ -5377,9 +6162,10 @@ inline void gcode_M205() { if (code_seen('S')) planner.min_feedrate_mm_s = code_value_linear_units(); if (code_seen('T')) planner.min_travel_feedrate_mm_s = code_value_linear_units(); if (code_seen('B')) planner.min_segment_time = code_value_millis(); - if (code_seen('X')) planner.max_xy_jerk = code_value_linear_units(); - if (code_seen('Z')) planner.max_z_jerk = code_value_axis_units(Z_AXIS); - if (code_seen('E')) planner.max_e_jerk = code_value_axis_units(E_AXIS); + if (code_seen('X')) planner.max_jerk[X_AXIS] = code_value_axis_units(X_AXIS); + if (code_seen('Y')) planner.max_jerk[Y_AXIS] = code_value_axis_units(Y_AXIS); + if (code_seen('Z')) planner.max_jerk[Z_AXIS] = code_value_axis_units(Z_AXIS); + if (code_seen('E')) planner.max_jerk[E_AXIS] = code_value_axis_units(E_AXIS); } /** @@ -5390,9 +6176,9 @@ inline void gcode_M206() { if (code_seen(axis_codes[i])) set_home_offset((AxisEnum)i, code_value_axis_units(i)); - #if ENABLED(SCARA) - if (code_seen('T')) set_home_offset(X_AXIS, code_value_axis_units(X_AXIS)); // Theta - if (code_seen('P')) set_home_offset(Y_AXIS, code_value_axis_units(Y_AXIS)); // Psi + #if ENABLED(MORGAN_SCARA) + if (code_seen('T')) set_home_offset(A_AXIS, code_value_axis_units(A_AXIS)); // Theta + if (code_seen('P')) set_home_offset(B_AXIS, code_value_axis_units(B_AXIS)); // Psi #endif SYNC_PLAN_POSITION_KINEMATIC(); @@ -5433,10 +6219,8 @@ inline void gcode_M206() { endstop_adj[i] = code_value_axis_units(i); #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPGM("endstop_adj["); - SERIAL_ECHO(axis_codes[i]); - SERIAL_ECHOPAIR("] = ", endstop_adj[i]); - SERIAL_EOL; + SERIAL_ECHOPAIR("endstop_adj[", axis_codes[i]); + SERIAL_ECHOLNPAIR("] = ", endstop_adj[i]); } #endif } @@ -5455,8 +6239,7 @@ inline void gcode_M206() { */ inline void gcode_M666() { if (code_seen('Z')) z_endstop_adj = code_value_axis_units(Z_AXIS); - SERIAL_ECHOPAIR("Z Endstop Adjustment set to (mm):", z_endstop_adj); - SERIAL_EOL; + SERIAL_ECHOLNPAIR("Z Endstop Adjustment set to (mm):", z_endstop_adj); } #endif // !DELTA && Z_DUAL_ENDSTOPS @@ -5497,28 +6280,45 @@ inline void gcode_M206() { /** * M209: Enable automatic retract (M209 S1) - * detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction. + * For slicers that don't support G10/11, reversed extrude-only + * moves will be classified as retraction. */ inline void gcode_M209() { if (code_seen('S')) { - int t = code_value_int(); - switch (t) { - case 0: - autoretract_enabled = false; - break; - case 1: - autoretract_enabled = true; - break; - default: - unknown_command_error(); - return; - } + autoretract_enabled = code_value_bool(); for (int i = 0; i < EXTRUDERS; i++) retracted[i] = false; } } #endif // FWRETRACT +/** + * M211: Enable, Disable, and/or Report software endstops + * + * Usage: M211 S1 to enable, M211 S0 to disable, M211 alone for report + */ +inline void gcode_M211() { + SERIAL_ECHO_START; + #if ENABLED(min_software_endstops) || ENABLED(max_software_endstops) + if (code_seen('S')) soft_endstops_enabled = code_value_bool(); + #endif + #if ENABLED(min_software_endstops) || ENABLED(max_software_endstops) + SERIAL_ECHOPGM(MSG_SOFT_ENDSTOPS); + serialprintPGM(soft_endstops_enabled ? PSTR(MSG_ON) : PSTR(MSG_OFF)); + #else + SERIAL_ECHOPGM(MSG_SOFT_ENDSTOPS); + SERIAL_ECHOPGM(MSG_OFF); + #endif + SERIAL_ECHOPGM(MSG_SOFT_MIN); + SERIAL_ECHOPAIR( MSG_X, soft_endstop_min[X_AXIS]); + SERIAL_ECHOPAIR(" " MSG_Y, soft_endstop_min[Y_AXIS]); + SERIAL_ECHOPAIR(" " MSG_Z, soft_endstop_min[Z_AXIS]); + SERIAL_ECHOPGM(MSG_SOFT_MAX); + SERIAL_ECHOPAIR( MSG_X, soft_endstop_max[X_AXIS]); + SERIAL_ECHOPAIR(" " MSG_Y, soft_endstop_max[Y_AXIS]); + SERIAL_ECHOLNPAIR(" " MSG_Z, soft_endstop_max[Z_AXIS]); +} + #if HOTENDS > 1 /** @@ -5530,7 +6330,7 @@ inline void gcode_M206() { * Z - Available with DUAL_X_CARRIAGE and SWITCHING_EXTRUDER */ inline void gcode_M218() { - if (get_target_extruder_from_command(218)) return; + if (get_target_extruder_from_command(218) || target_extruder == 0) return; if (code_seen('X')) hotend_offset[X_AXIS][target_extruder] = code_value_axis_units(X_AXIS); if (code_seen('Y')) hotend_offset[Y_AXIS][target_extruder] = code_value_axis_units(Y_AXIS); @@ -5569,7 +6369,7 @@ inline void gcode_M220() { inline void gcode_M221() { if (get_target_extruder_from_command(221)) return; if (code_seen('S')) - extruder_multiplier[target_extruder] = code_value_int(); + flow_percentage[target_extruder] = code_value_int(); } /** @@ -5577,47 +6377,87 @@ inline void gcode_M221() { */ inline void gcode_M226() { if (code_seen('P')) { - int pin_number = code_value_int(); + int pin_number = code_value_int(), + pin_state = code_seen('S') ? code_value_int() : -1; // required pin state - default is inverted - int pin_state = code_seen('S') ? code_value_int() : -1; // required pin state - default is inverted + if (pin_state >= -1 && pin_state <= 1 && pin_number > -1 && !pin_is_protected(pin_number)) { - if (pin_state >= -1 && pin_state <= 1) { + int target = LOW; - for (uint8_t i = 0; i < COUNT(sensitive_pins); i++) { - if (sensitive_pins[i] == pin_number) { - pin_number = -1; + stepper.synchronize(); + + pinMode(pin_number, INPUT); + switch (pin_state) { + case 1: + target = HIGH; + break; + case 0: + target = LOW; + break; + case -1: + target = !digitalRead(pin_number); break; - } } - if (pin_number > -1) { - int target = LOW; + while (digitalRead(pin_number) != target) idle(); - stepper.synchronize(); - - pinMode(pin_number, INPUT); - - switch (pin_state) { - case 1: - target = HIGH; - break; - - case 0: - target = LOW; - break; - - case -1: - target = !digitalRead(pin_number); - break; - } - - while (digitalRead(pin_number) != target) idle(); - - } // pin_number > -1 - } // pin_state -1 0 1 + } // pin_state -1 0 1 && pin_number > -1 } // code_seen('P') } +#if ENABLED(EXPERIMENTAL_I2CBUS) + + /** + * M260: Send data to a I2C slave device + * + * This is a PoC, the formating and arguments for the GCODE will + * change to be more compatible, the current proposal is: + * + * M260 A ; Sets the I2C slave address the data will be sent to + * + * M260 B + * M260 B + * M260 B + * + * M260 S1 ; Send the buffered data and reset the buffer + * M260 R1 ; Reset the buffer without sending data + * + */ + inline void gcode_M260() { + // Set the target address + if (code_seen('A')) i2c.address(code_value_byte()); + + // Add a new byte to the buffer + if (code_seen('B')) i2c.addbyte(code_value_byte()); + + // Flush the buffer to the bus + if (code_seen('S')) i2c.send(); + + // Reset and rewind the buffer + else if (code_seen('R')) i2c.reset(); + } + + /** + * M261: Request X bytes from I2C slave device + * + * Usage: M261 A B + */ + inline void gcode_M261() { + if (code_seen('A')) i2c.address(code_value_byte()); + + uint8_t bytes = code_seen('B') ? code_value_byte() : 1; + + if (i2c.addr && bytes && bytes <= TWIBUS_BUFFER_SIZE) { + i2c.relay(bytes); + } + else { + SERIAL_ERROR_START; + SERIAL_ERRORLN("Bad i2c request"); + } + } + +#endif // EXPERIMENTAL_I2CBUS + #if HAS_SERVOS /** @@ -5631,17 +6471,14 @@ inline void gcode_M226() { MOVE_SERVO(servo_index, code_value_int()); else { SERIAL_ECHO_START; - SERIAL_ECHOPGM(" Servo "); - SERIAL_ECHO(servo_index); - SERIAL_ECHOPGM(": "); - SERIAL_ECHOLN(servo[servo_index].read()); + SERIAL_ECHOPAIR(" Servo ", servo_index); + SERIAL_ECHOLNPAIR(": ", servo[servo_index].read()); } } else { SERIAL_ERROR_START; - SERIAL_ERROR("Servo "); - SERIAL_ERROR(servo_index); - SERIAL_ERRORLN(" out of range"); + SERIAL_ECHOPAIR("Servo ", servo_index); + SERIAL_ECHOLNPGM(" out of range"); } } @@ -5697,19 +6534,14 @@ inline void gcode_M226() { thermalManager.updatePID(); SERIAL_ECHO_START; #if ENABLED(PID_PARAMS_PER_HOTEND) - SERIAL_ECHOPGM(" e:"); // specify extruder in serial output - SERIAL_ECHO(e); + SERIAL_ECHOPAIR(" e:", e); // specify extruder in serial output #endif // PID_PARAMS_PER_HOTEND - SERIAL_ECHOPGM(" p:"); - SERIAL_ECHO(PID_PARAM(Kp, e)); - SERIAL_ECHOPGM(" i:"); - SERIAL_ECHO(unscalePID_i(PID_PARAM(Ki, e))); - SERIAL_ECHOPGM(" d:"); - SERIAL_ECHO(unscalePID_d(PID_PARAM(Kd, e))); + SERIAL_ECHOPAIR(" p:", PID_PARAM(Kp, e)); + SERIAL_ECHOPAIR(" i:", unscalePID_i(PID_PARAM(Ki, e))); + SERIAL_ECHOPAIR(" d:", unscalePID_d(PID_PARAM(Kd, e))); #if ENABLED(PID_EXTRUSION_SCALING) - SERIAL_ECHOPGM(" c:"); //Kc does not have scaling applied above, or in resetting defaults - SERIAL_ECHO(PID_PARAM(Kc, e)); + SERIAL_ECHOPAIR(" c:", PID_PARAM(Kc, e)); #endif SERIAL_EOL; } @@ -5731,12 +6563,9 @@ inline void gcode_M226() { thermalManager.updatePID(); SERIAL_ECHO_START; - SERIAL_ECHOPGM(" p:"); - SERIAL_ECHO(thermalManager.bedKp); - SERIAL_ECHOPGM(" i:"); - SERIAL_ECHO(unscalePID_i(thermalManager.bedKi)); - SERIAL_ECHOPGM(" d:"); - SERIAL_ECHOLN(unscalePID_d(thermalManager.bedKd)); + SERIAL_ECHOPAIR(" p:", thermalManager.bedKp); + SERIAL_ECHOPAIR(" i:", unscalePID_i(thermalManager.bedKi)); + SERIAL_ECHOLNPAIR(" d:", unscalePID_d(thermalManager.bedKd)); } #endif // PIDTEMPBED @@ -5791,7 +6620,7 @@ inline void gcode_M226() { #endif // HAS_LCD_CONTRAST -#if ENABLED(PREVENT_DANGEROUS_EXTRUDE) +#if ENABLED(PREVENT_COLD_EXTRUSION) /** * M302: Allow cold extrudes, or set the minimum extrude temperature @@ -5826,7 +6655,7 @@ inline void gcode_M226() { } } -#endif // PREVENT_DANGEROUS_EXTRUDE +#endif // PREVENT_COLD_EXTRUSION /** * M303: PID relay autotune @@ -5858,19 +6687,15 @@ inline void gcode_M303() { #endif } -#if ENABLED(SCARA) - bool SCARA_move_to_cal(uint8_t delta_x, uint8_t delta_y) { - //SoftEndsEnabled = false; // Ignore soft endstops during calibration - //SERIAL_ECHOLNPGM(" Soft endstops disabled"); +#if ENABLED(MORGAN_SCARA) + + bool SCARA_move_to_cal(uint8_t delta_a, uint8_t delta_b) { if (IsRunning()) { - //gcode_get_destination(); // For X Y Z E F - delta[X_AXIS] = delta_x; - delta[Y_AXIS] = delta_y; - forward_kinematics_SCARA(delta); - destination[X_AXIS] = delta[X_AXIS] / axis_scaling[X_AXIS]; - destination[Y_AXIS] = delta[Y_AXIS] / axis_scaling[Y_AXIS]; + forward_kinematics_SCARA(delta_a, delta_b); + destination[X_AXIS] = LOGICAL_X_POSITION(cartes[X_AXIS]); + destination[Y_AXIS] = LOGICAL_Y_POSITION(cartes[Y_AXIS]); + destination[Z_AXIS] = current_position[Z_AXIS]; prepare_move_to_destination(); - //ok_to_send(); return true; } return false; @@ -5916,15 +6741,6 @@ inline void gcode_M303() { return SCARA_move_to_cal(45, 135); } - /** - * M365: SCARA calibration: Scaling factor, X, Y, Z axis - */ - inline void gcode_M365() { - LOOP_XYZ(i) - if (code_seen(axis_codes[i])) - axis_scaling[i] = code_value_float(); - } - #endif // SCARA #if ENABLED(EXT_SOLENOID) @@ -6020,13 +6836,13 @@ inline void gcode_M400() { stepper.synchronize(); } if (code_seen('D')) meas_delay_cm = code_value_int(); NOMORE(meas_delay_cm, MAX_MEASUREMENT_DELAY); - if (filwidth_delay_index2 == -1) { // Initialize the ring buffer if not done since startup + if (filwidth_delay_index[1] == -1) { // Initialize the ring buffer if not done since startup int temp_ratio = thermalManager.widthFil_to_size_ratio(); for (uint8_t i = 0; i < COUNT(measurement_delay); ++i) measurement_delay[i] = temp_ratio - 100; // Subtract 100 to scale within a signed byte - filwidth_delay_index1 = filwidth_delay_index2 = 0; + filwidth_delay_index[0] = filwidth_delay_index[1] = 0; } filament_sensor = true; @@ -6034,7 +6850,7 @@ inline void gcode_M400() { stepper.synchronize(); } //SERIAL_PROTOCOLPGM("Filament dia (measured mm):"); //SERIAL_PROTOCOL(filament_width_meas); //SERIAL_PROTOCOLPGM("Extrusion ratio(%):"); - //SERIAL_PROTOCOL(extruder_multiplier[active_extruder]); + //SERIAL_PROTOCOL(flow_percentage[active_extruder]); } /** @@ -6054,19 +6870,27 @@ inline void gcode_M400() { stepper.synchronize(); } void quickstop_stepper() { stepper.quick_stop(); - #if DISABLED(SCARA) - stepper.synchronize(); - LOOP_XYZ(i) set_current_from_steppers_for_axis((AxisEnum)i); - SYNC_PLAN_POSITION_KINEMATIC(); - #endif + stepper.synchronize(); + set_current_from_steppers_for_axis(ALL_AXES); + SYNC_PLAN_POSITION_KINEMATIC(); } -#if ENABLED(MESH_BED_LEVELING) - +#if PLANNER_LEVELING /** - * M420: Enable/Disable Mesh Bed Leveling + * M420: Enable/Disable Bed Leveling and/or set the Z fade height. + * + * S[bool] Turns leveling on or off + * Z[height] Sets the Z fade height (0 or none to disable) */ - inline void gcode_M420() { if (code_seen('S') && code_has_value()) mbl.set_has_mesh(code_value_bool()); } + inline void gcode_M420() { + if (code_seen('S')) set_bed_leveling_enabled(code_value_bool()); + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + if (code_seen('Z')) set_z_fade_height(code_value_linear_units()); + #endif + } +#endif + +#if ENABLED(MESH_BED_LEVELING) /** * M421: Set a single Mesh Bed Leveling Z coordinate @@ -6122,7 +6946,7 @@ inline void gcode_M428() { bool err = false; LOOP_XYZ(i) { if (axis_homed[i]) { - float base = (current_position[i] > (sw_endstop_min[i] + sw_endstop_max[i]) * 0.5) ? base_home_pos(i) : 0, + float base = (current_position[i] > (soft_endstop_min[i] + soft_endstop_max[i]) * 0.5) ? base_home_pos((AxisEnum)i) : 0, diff = current_position[i] - LOGICAL_POSITION(base, i); if (diff > -20 && diff < 20) { set_home_offset((AxisEnum)i, home_offset[i] - diff); @@ -6201,11 +7025,9 @@ inline void gcode_M503() { SERIAL_ECHO(zprobe_zoffset); } else { - SERIAL_ECHOPGM(MSG_Z_MIN); - SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MIN); + SERIAL_ECHOPAIR(MSG_Z_MIN, Z_PROBE_OFFSET_RANGE_MIN); SERIAL_CHAR(' '); - SERIAL_ECHOPGM(MSG_Z_MAX); - SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MAX); + SERIAL_ECHOPAIR(MSG_Z_MAX, Z_PROBE_OFFSET_RANGE_MAX); } } else { @@ -6250,11 +7072,10 @@ inline void gcode_M503() { lastpos[i] = destination[i] = current_position[i]; // Define runplan for move axes - #if ENABLED(DELTA) - #define RUNPLAN(RATE_MM_S) inverse_kinematics(destination); \ - planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], destination[E_AXIS], RATE_MM_S, active_extruder); + #if IS_KINEMATIC + #define RUNPLAN(RATE_MM_S) planner.buffer_line_kinematic(destination, RATE_MM_S, active_extruder); #else - #define RUNPLAN(RATE_MM_S) line_to_destination(MMS_TO_MMM(RATE_MM_S)); + #define RUNPLAN(RATE_MM_S) line_to_destination(RATE_MM_S); #endif KEEPALIVE_STATE(IN_HANDLER); @@ -6315,25 +7136,25 @@ inline void gcode_M503() { delay(100); #if HAS_BUZZER - millis_t next_tick = 0; + millis_t next_buzz = 0; #endif // Wait for filament insert by user and press button lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_INSERT); - while (!lcd_clicked()) { + // LCD click or M108 will clear this + wait_for_user = true; + + while (wait_for_user) { #if HAS_BUZZER millis_t ms = millis(); - if (ms >= next_tick) { + if (ms >= next_buzz) { BUZZ(300, 2000); - next_tick = ms + 2500; // Beep every 2.5s while waiting + next_buzz = ms + 2500; // Beep every 2.5s while waiting } #endif idle(true); } - delay(100); - while (lcd_clicked()) idle(true); - delay(100); // Show load message lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_LOAD); @@ -6367,17 +7188,14 @@ inline void gcode_M503() { KEEPALIVE_STATE(IN_HANDLER); // Set extruder to saved position - current_position[E_AXIS] = lastpos[E_AXIS]; - destination[E_AXIS] = lastpos[E_AXIS]; + destination[E_AXIS] = current_position[E_AXIS] = lastpos[E_AXIS]; planner.set_e_position_mm(current_position[E_AXIS]); - #if ENABLED(DELTA) - // Move XYZ to starting position, then E - inverse_kinematics(lastpos); - planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], destination[E_AXIS], FILAMENT_CHANGE_XY_FEEDRATE, active_extruder); - planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], lastpos[E_AXIS], FILAMENT_CHANGE_XY_FEEDRATE, active_extruder); + #if IS_KINEMATIC + // Move XYZ to starting position + planner.buffer_line_kinematic(lastpos, FILAMENT_CHANGE_XY_FEEDRATE, active_extruder); #else - // Move XY to starting position, then Z, then E + // Move XY to starting position, then Z destination[X_AXIS] = lastpos[X_AXIS]; destination[Y_AXIS] = lastpos[Y_AXIS]; RUNPLAN(FILAMENT_CHANGE_XY_FEEDRATE); @@ -6412,8 +7230,11 @@ inline void gcode_M503() { */ inline void gcode_M605() { stepper.synchronize(); - if (code_seen('S')) dual_x_carriage_mode = code_value_byte(); + if (code_seen('S')) dual_x_carriage_mode = (DualXMode)code_value_byte(); switch (dual_x_carriage_mode) { + case DXC_FULL_CONTROL_MODE: + case DXC_AUTO_PARK_MODE: + break; case DXC_DUPLICATION_MODE: if (code_seen('X')) duplicate_extruder_x_offset = max(code_value_axis_units(X_AXIS), X2_MIN_POS - x_home_pos(0)); if (code_seen('R')) duplicate_extruder_temp_offset = code_value_temp_diff(); @@ -6428,9 +7249,6 @@ inline void gcode_M503() { SERIAL_CHAR(','); SERIAL_ECHOLN(hotend_offset[Y_AXIS][1]); break; - case DXC_FULL_CONTROL_MODE: - case DXC_AUTO_PARK_MODE: - break; default: dual_x_carriage_mode = DEFAULT_DUAL_X_CARRIAGE_MODE; break; @@ -6446,8 +7264,7 @@ inline void gcode_M503() { stepper.synchronize(); extruder_duplication_enabled = code_seen('S') && code_value_int() == 2; SERIAL_ECHO_START; - SERIAL_ECHOPAIR(MSG_DUPLICATION_MODE, extruder_duplication_enabled ? MSG_ON : MSG_OFF); - SERIAL_EOL; + SERIAL_ECHOLNPAIR(MSG_DUPLICATION_MODE, extruder_duplication_enabled ? MSG_ON : MSG_OFF); } #endif // M605 @@ -6458,7 +7275,7 @@ inline void gcode_M503() { */ inline void gcode_M905() { stepper.synchronize(); - stepper.advance_M905(code_seen('K') ? code_value_float() : -1.0); + planner.advance_M905(code_seen('K') ? code_value_float() : -1.0); } #endif @@ -6468,18 +7285,19 @@ inline void gcode_M503() { inline void gcode_M907() { #if HAS_DIGIPOTSS LOOP_XYZE(i) - if (code_seen(axis_codes[i])) stepper.digipot_current(i, code_value_int()); + if (code_seen(axis_codes[i])) stepper.digipot_current(i, code_value_int()); if (code_seen('B')) stepper.digipot_current(4, code_value_int()); if (code_seen('S')) for (int i = 0; i <= 4; i++) stepper.digipot_current(i, code_value_int()); - #endif - #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) - if (code_seen('X')) stepper.digipot_current(0, code_value_int()); - #endif - #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) - if (code_seen('Z')) stepper.digipot_current(1, code_value_int()); - #endif - #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) - if (code_seen('E')) stepper.digipot_current(2, code_value_int()); + #elif HAS_MOTOR_CURRENT_PWM + #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) + if (code_seen('X')) stepper.digipot_current(0, code_value_int()); + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) + if (code_seen('Z')) stepper.digipot_current(1, code_value_int()); + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) + if (code_seen('E')) stepper.digipot_current(2, code_value_int()); + #endif #endif #if ENABLED(DIGIPOT_I2C) // this one uses actual amps in floating point @@ -6556,6 +7374,32 @@ inline void gcode_M907() { #endif // HAS_MICROSTEPS +#if HAS_CASE_LIGHT + + uint8_t case_light_brightness = 255; + + void update_case_light() { + digitalWrite(CASE_LIGHT_PIN, case_light_on != INVERT_CASE_LIGHT ? HIGH : LOW); + analogWrite(CASE_LIGHT_PIN, case_light_on != INVERT_CASE_LIGHT ? case_light_brightness : 0); + } + + /** + * M355: Turn case lights on/off and set brightness + * + * S Turn case light on or off + * P Set case light brightness (PWM pin required) + */ + inline void gcode_M355() { + if (code_seen('P')) case_light_brightness = code_value_byte(); + if (code_seen('S')) case_light_on = code_value_bool(); + update_case_light(); + SERIAL_ECHO_START; + SERIAL_ECHOPGM("Case lights "); + case_light_on ? SERIAL_ECHOLNPGM("on") : SERIAL_ECHOLNPGM("off"); + } + +#endif // HAS_CASE_LIGHT + #if ENABLED(MIXING_EXTRUDER) /** @@ -6568,8 +7412,11 @@ inline void gcode_M907() { */ inline void gcode_M163() { int mix_index = code_seen('S') ? code_value_int() : 0; - float mix_value = code_seen('P') ? code_value_float() : 0.0; - if (mix_index < MIXING_STEPPERS) mixing_factor[mix_index] = mix_value; + if (mix_index < MIXING_STEPPERS) { + float mix_value = code_seen('P') ? code_value_float() : 0.0; + NOLESS(mix_value, 0.0); + mixing_factor[mix_index] = RECIPROCAL(mix_value); + } } #if MIXING_VIRTUAL_TOOLS > 1 @@ -6644,13 +7491,15 @@ inline void invalid_extruder_error(const uint8_t &e) { SERIAL_ECHOLN(MSG_INVALID_EXTRUDER); } -void tool_change(const uint8_t tmp_extruder, const float fr_mm_m/*=0.0*/, bool no_move/*=false*/) { +/** + * Perform a tool-change, which may result in moving the + * previous tool out of the way and the new tool into place. + */ +void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool no_move/*=false*/) { #if ENABLED(MIXING_EXTRUDER) && MIXING_VIRTUAL_TOOLS > 1 - if (tmp_extruder >= MIXING_VIRTUAL_TOOLS) { - invalid_extruder_error(tmp_extruder); - return; - } + if (tmp_extruder >= MIXING_VIRTUAL_TOOLS) + return invalid_extruder_error(tmp_extruder); // T0-Tnnn: Switch virtual tool by changing the mix for (uint8_t j = 0; j < MIXING_STEPPERS; j++) @@ -6660,14 +7509,12 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_m/*=0.0*/, bool n #if HOTENDS > 1 - if (tmp_extruder >= EXTRUDERS) { - invalid_extruder_error(tmp_extruder); - return; - } + if (tmp_extruder >= EXTRUDERS) + return invalid_extruder_error(tmp_extruder); - float old_feedrate_mm_m = feedrate_mm_m; + float old_feedrate_mm_s = feedrate_mm_s; - feedrate_mm_m = fr_mm_m > 0.0 ? (old_feedrate_mm_m = fr_mm_m) : XY_PROBE_FEEDRATE_MM_M; + feedrate_mm_s = fr_mm_s > 0.0 ? (old_feedrate_mm_s = fr_mm_s) : XY_PROBE_FEEDRATE_MM_S; if (tmp_extruder != active_extruder) { if (!no_move && axis_unhomed_error(true, true, true)) { @@ -6684,29 +7531,35 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_m/*=0.0*/, bool n if (DEBUGGING(LEVELING)) { SERIAL_ECHOPGM("Dual X Carriage Mode "); switch (dual_x_carriage_mode) { - case DXC_DUPLICATION_MODE: SERIAL_ECHOLNPGM("DXC_DUPLICATION_MODE"); break; - case DXC_AUTO_PARK_MODE: SERIAL_ECHOLNPGM("DXC_AUTO_PARK_MODE"); break; case DXC_FULL_CONTROL_MODE: SERIAL_ECHOLNPGM("DXC_FULL_CONTROL_MODE"); break; + case DXC_AUTO_PARK_MODE: SERIAL_ECHOLNPGM("DXC_AUTO_PARK_MODE"); break; + case DXC_DUPLICATION_MODE: SERIAL_ECHOLNPGM("DXC_DUPLICATION_MODE"); break; } } #endif - if (dual_x_carriage_mode == DXC_AUTO_PARK_MODE && IsRunning() && - (delayed_move_time || current_position[X_AXIS] != x_home_pos(active_extruder)) + const float xhome = x_home_pos(active_extruder); + if (dual_x_carriage_mode == DXC_AUTO_PARK_MODE + && IsRunning() + && (delayed_move_time || current_position[X_AXIS] != xhome) ) { + float raised_z = current_position[Z_AXIS] + TOOLCHANGE_PARK_ZLIFT; + #if ENABLED(max_software_endstops) + NOMORE(raised_z, soft_endstop_max[Z_AXIS]); + #endif #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR("Raise to ", current_position[Z_AXIS] + TOOLCHANGE_PARK_ZLIFT); SERIAL_EOL; - SERIAL_ECHOPAIR("MoveX to ", x_home_pos(active_extruder)); SERIAL_EOL; - SERIAL_ECHOPAIR("Lower to ", current_position[Z_AXIS]); SERIAL_EOL; + SERIAL_ECHOLNPAIR("Raise to ", raised_z); + SERIAL_ECHOLNPAIR("MoveX to ", xhome); + SERIAL_ECHOLNPAIR("Lower to ", current_position[Z_AXIS]); } #endif // Park old head: 1) raise 2) move to park position 3) lower for (uint8_t i = 0; i < 3; i++) planner.buffer_line( - i == 0 ? current_position[X_AXIS] : x_home_pos(active_extruder), + i == 0 ? current_position[X_AXIS] : xhome, current_position[Y_AXIS], - current_position[Z_AXIS] + (i == 2 ? 0 : TOOLCHANGE_PARK_ZLIFT), + i == 2 ? current_position[Z_AXIS] : raised_z, current_position[E_AXIS], planner.max_feedrate_mm_s[i == 1 ? X_AXIS : Z_AXIS], active_extruder @@ -6714,9 +7567,11 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_m/*=0.0*/, bool n stepper.synchronize(); } - // apply Y & Z extruder offset (x offset is already used in determining home pos) + // Apply Y & Z extruder offset (X offset is used as home pos with Dual X) current_position[Y_AXIS] -= hotend_offset[Y_AXIS][active_extruder] - hotend_offset[Y_AXIS][tmp_extruder]; current_position[Z_AXIS] -= hotend_offset[Z_AXIS][active_extruder] - hotend_offset[Z_AXIS][tmp_extruder]; + + // Activate the new extruder active_extruder = tmp_extruder; // This function resets the max/min values - the current position may be overwritten below. @@ -6726,13 +7581,31 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_m/*=0.0*/, bool n if (DEBUGGING(LEVELING)) DEBUG_POS("New Extruder", current_position); #endif + // Only when auto-parking are carriages safe to move + if (dual_x_carriage_mode != DXC_AUTO_PARK_MODE) no_move = true; + switch (dual_x_carriage_mode) { case DXC_FULL_CONTROL_MODE: + // New current position is the position of the activated extruder current_position[X_AXIS] = LOGICAL_X_POSITION(inactive_extruder_x_pos); + // Save the inactive extruder's position (from the old current_position) inactive_extruder_x_pos = RAW_X_POSITION(destination[X_AXIS]); break; + case DXC_AUTO_PARK_MODE: + // record raised toolhead position for use by unpark + memcpy(raised_parked_position, current_position, sizeof(raised_parked_position)); + raised_parked_position[Z_AXIS] += TOOLCHANGE_UNPARK_ZLIFT; + #if ENABLED(max_software_endstops) + NOMORE(raised_parked_position[Z_AXIS], soft_endstop_max[Z_AXIS]); + #endif + active_extruder_parked = true; + delayed_move_time = 0; + break; case DXC_DUPLICATION_MODE: - active_extruder_parked = (active_extruder == 0); // this triggers the second extruder to move into the duplication position + // If the new extruder is the left one, set it "parked" + // This triggers the second extruder to move into the duplication position + active_extruder_parked = (active_extruder == 0); + if (active_extruder_parked) current_position[X_AXIS] = LOGICAL_X_POSITION(inactive_extruder_x_pos); else @@ -6740,24 +7613,16 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_m/*=0.0*/, bool n inactive_extruder_x_pos = RAW_X_POSITION(destination[X_AXIS]); extruder_duplication_enabled = false; break; - default: - // record raised toolhead position for use by unpark - memcpy(raised_parked_position, current_position, sizeof(raised_parked_position)); - raised_parked_position[Z_AXIS] += TOOLCHANGE_UNPARK_ZLIFT; - active_extruder_parked = true; - delayed_move_time = 0; - break; } #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR("Active extruder parked: ", active_extruder_parked ? "yes" : "no"); - SERIAL_EOL; + SERIAL_ECHOLNPAIR("Active extruder parked: ", active_extruder_parked ? "yes" : "no"); DEBUG_POS("New extruder (parked)", current_position); } #endif - // No extra case for AUTO_BED_LEVELING_FEATURE in DUAL_X_CARRIAGE. Does that mean they don't work together? + // No extra case for HAS_ABL in DUAL_X_CARRIAGE. Does that mean they don't work together? #else // !DUAL_X_CARRIAGE #if ENABLED(SWITCHING_EXTRUDER) @@ -6765,15 +7630,9 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_m/*=0.0*/, bool n float z_diff = hotend_offset[Z_AXIS][active_extruder] - hotend_offset[Z_AXIS][tmp_extruder], z_raise = 0.3 + (z_diff > 0.0 ? z_diff : 0.0); - // Always raise by some amount - planner.buffer_line( - current_position[X_AXIS], - current_position[Y_AXIS], - current_position[Z_AXIS] + z_raise, - current_position[E_AXIS], - planner.max_feedrate_mm_s[Z_AXIS], - active_extruder - ); + // Always raise by some amount (destination copied from current_position earlier) + destination[Z_AXIS] += z_raise; + planner.buffer_line_kinematic(destination, planner.max_feedrate_mm_s[Z_AXIS], active_extruder); stepper.synchronize(); move_extruder_servo(active_extruder); @@ -6781,14 +7640,8 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_m/*=0.0*/, bool n // Move back down, if needed if (z_raise != z_diff) { - planner.buffer_line( - current_position[X_AXIS], - current_position[Y_AXIS], - current_position[Z_AXIS] + z_diff, - current_position[E_AXIS], - planner.max_feedrate_mm_s[Z_AXIS], - active_extruder - ); + destination[Z_AXIS] = current_position[Z_AXIS] + z_diff; + planner.buffer_line_kinematic(destination, planner.max_feedrate_mm_s[Z_AXIS], active_extruder); stepper.synchronize(); } #endif @@ -6816,7 +7669,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_m/*=0.0*/, bool n * Z software endstop. But this is technically correct (and * there is no viable alternative). */ - #if ENABLED(AUTO_BED_LEVELING_FEATURE) + #if ABL_PLANAR // Offset extruder, make sure to apply the bed level rotation matrix vector_3 tmp_offset_vec = vector_3(hotend_offset[X_AXIS][tmp_extruder], hotend_offset[Y_AXIS][tmp_extruder], @@ -6844,7 +7697,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_m/*=0.0*/, bool n float xydiff[2] = { offset_vec.x, offset_vec.y }; current_position[Z_AXIS] += offset_vec.z; - #else // !AUTO_BED_LEVELING_FEATURE + #else // !ABL_PLANAR float xydiff[2] = { hotend_offset[X_AXIS][tmp_extruder] - hotend_offset[X_AXIS][active_extruder], @@ -6857,20 +7710,21 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_m/*=0.0*/, bool n #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) SERIAL_ECHOPAIR("Z before MBL: ", current_position[Z_AXIS]); #endif - float xpos = RAW_CURRENT_POSITION(X_AXIS), - ypos = RAW_CURRENT_POSITION(Y_AXIS); - current_position[Z_AXIS] += mbl.get_z(xpos + xydiff[X_AXIS], ypos + xydiff[Y_AXIS]) - mbl.get_z(xpos, ypos); + float x2 = current_position[X_AXIS] + xydiff[X_AXIS], + y2 = current_position[Y_AXIS] + xydiff[Y_AXIS], + z1 = current_position[Z_AXIS], z2 = z1; + planner.apply_leveling(current_position[X_AXIS], current_position[Y_AXIS], z1); + planner.apply_leveling(x2, y2, z2); + current_position[Z_AXIS] += z2 - z1; #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR(" after: ", current_position[Z_AXIS]); - SERIAL_EOL; - } + if (DEBUGGING(LEVELING)) + SERIAL_ECHOLNPAIR(" after: ", current_position[Z_AXIS]); #endif } #endif // MESH_BED_LEVELING - #endif // !AUTO_BED_LEVELING_FEATURE + #endif // !HAS_ABL #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { @@ -6917,21 +7771,20 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_m/*=0.0*/, bool n enable_solenoid_on_active_extruder(); #endif // EXT_SOLENOID - feedrate_mm_m = old_feedrate_mm_m; + feedrate_mm_s = old_feedrate_mm_s; #else // HOTENDS <= 1 // Set the new active extruder active_extruder = tmp_extruder; - UNUSED(fr_mm_m); + UNUSED(fr_mm_s); UNUSED(no_move); #endif // HOTENDS <= 1 SERIAL_ECHO_START; - SERIAL_ECHOPGM(MSG_ACTIVE_EXTRUDER); - SERIAL_PROTOCOLLN((int)active_extruder); + SERIAL_ECHOLNPAIR(MSG_ACTIVE_EXTRUDER, (int)active_extruder); #endif //!MIXING_EXTRUDER || MIXING_VIRTUAL_TOOLS <= 1 } @@ -6947,7 +7800,8 @@ inline void gcode_T(uint8_t tmp_extruder) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR(">>> gcode_T(", tmp_extruder); - SERIAL_ECHOLNPGM(")"); + SERIAL_CHAR(')'); + SERIAL_EOL; DEBUG_POS("BEFORE", current_position); } #endif @@ -6960,7 +7814,7 @@ inline void gcode_T(uint8_t tmp_extruder) { tool_change( tmp_extruder, - code_seen('F') ? code_value_axis_units(X_AXIS) : 0.0, + code_seen('F') ? MMM_TO_MMS(code_value_axis_units(X_AXIS)) : 0.0, (tmp_extruder == active_extruder) || (code_seen('S') && code_value_bool()) ); @@ -7007,6 +7861,11 @@ void process_next_command() { // Skip spaces to get the numeric part while (*cmd_ptr == ' ') cmd_ptr++; + // Allow for decimal point in command + #if ENABLED(G38_PROBE_TARGET) + uint8_t subcode = 0; + #endif + uint16_t codenum = 0; // define ahead of goto // Bail early if there's no code @@ -7019,6 +7878,15 @@ void process_next_command() { cmd_ptr++; } while (NUMERIC(*cmd_ptr)); + // Allow for decimal point in command + #if ENABLED(G38_PROBE_TARGET) + if (*cmd_ptr == '.') { + cmd_ptr++; + while (NUMERIC(*cmd_ptr)) + subcode = (subcode * 10) + (*cmd_ptr++ - '0'); + } + #endif + // Skip all spaces to get to the first argument, or nul while (*cmd_ptr == ' ') cmd_ptr++; @@ -7034,7 +7902,11 @@ void process_next_command() { // G0, G1 case 0: case 1: - gcode_G0_G1(); + #if IS_SCARA + gcode_G0_G1(codenum == 0); + #else + gcode_G0_G1(); + #endif break; // G2, G3 @@ -7090,11 +7962,11 @@ void process_next_command() { gcode_G28(); break; - #if ENABLED(AUTO_BED_LEVELING_FEATURE) || ENABLED(MESH_BED_LEVELING) + #if PLANNER_LEVELING case 29: // G29 Detailed Z probe, probes the bed at 3 or more points. gcode_G29(); break; - #endif // AUTO_BED_LEVELING_FEATURE + #endif // PLANNER_LEVELING #if HAS_BED_PROBE @@ -7115,6 +7987,13 @@ void process_next_command() { #endif // Z_PROBE_SLED #endif // HAS_BED_PROBE + #if ENABLED(G38_PROBE_TARGET) + case 38: // G38.2 & G38.3 + if (subcode == 2 || subcode == 3) + gcode_G38(subcode == 2); + break; + #endif + case 90: // G90 relative_mode = false; break; @@ -7129,91 +8008,88 @@ void process_next_command() { break; case 'M': switch (codenum) { - #if ENABLED(ULTIPANEL) - case 0: // M0 - Unconditional stop - Wait for user button press on LCD - case 1: // M1 - Conditional stop - Wait for user button press on LCD + #if ENABLED(ULTIPANEL) || ENABLED(EMERGENCY_PARSER) + case 0: // M0: Unconditional stop - Wait for user button press on LCD + case 1: // M1: Conditional stop - Wait for user button press on LCD gcode_M0_M1(); break; #endif // ULTIPANEL - case 17: + case 17: // M17: Enable all stepper motors gcode_M17(); break; #if ENABLED(SDSUPPORT) - case 20: // M20 - list SD card + case 20: // M20: list SD card gcode_M20(); break; - case 21: // M21 - init SD card + case 21: // M21: init SD card gcode_M21(); break; - case 22: //M22 - release SD card + case 22: // M22: release SD card gcode_M22(); break; - case 23: //M23 - Select file + case 23: // M23: Select file gcode_M23(); break; - case 24: //M24 - Start SD print + case 24: // M24: Start SD print gcode_M24(); break; - case 25: //M25 - Pause SD print + case 25: // M25: Pause SD print gcode_M25(); break; - case 26: //M26 - Set SD index + case 26: // M26: Set SD index gcode_M26(); break; - case 27: //M27 - Get SD status + case 27: // M27: Get SD status gcode_M27(); break; - case 28: //M28 - Start SD write + case 28: // M28: Start SD write gcode_M28(); break; - case 29: //M29 - Stop SD write + case 29: // M29: Stop SD write gcode_M29(); break; - case 30: //M30 Delete File + case 30: // M30 Delete File gcode_M30(); break; - case 32: //M32 - Select file and start SD print + case 32: // M32: Select file and start SD print gcode_M32(); break; #if ENABLED(LONG_FILENAME_HOST_SUPPORT) - case 33: //M33 - Get the long full path to a file or folder + case 33: // M33: Get the long full path to a file or folder gcode_M33(); break; - #endif // LONG_FILENAME_HOST_SUPPORT + #endif - case 928: //M928 - Start SD write + case 928: // M928: Start SD write gcode_M928(); break; #endif //SDSUPPORT - case 31: //M31 take time since the start of the SD print or an M109 command - gcode_M31(); - break; + case 31: // M31: Report time since the start of SD print or last M109 + gcode_M31(); break; - case 42: //M42 -Change pin status via gcode - gcode_M42(); - break; + case 42: // M42: Change pin state + gcode_M42(); break; + + #if ENABLED(PINS_DEBUGGING) + case 43: // M43: Read pin state + gcode_M43(); break; + #endif #if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) - case 48: // M48 Z probe repeatability + case 48: // M48: Z probe repeatability test gcode_M48(); break; #endif // Z_MIN_PROBE_REPEATABILITY_TEST - case 75: // Start print timer - gcode_M75(); - break; - - case 76: // Pause print timer - gcode_M76(); - break; - - case 77: // Stop print timer - gcode_M77(); - break; + case 75: // M75: Start print timer + gcode_M75(); break; + case 76: // M76: Pause print timer + gcode_M76(); break; + case 77: // M77: Stop print timer + gcode_M77(); break; #if ENABLED(PRINTCOUNTER) - case 78: // Show print statistics - gcode_M78(); - break; + case 78: // M78: Show print statistics + gcode_M78(); break; #endif #if ENABLED(M100_FREE_MEMORY_WATCHER) - case 100: + case 100: // M100: Free Memory Report gcode_M100(); break; #endif - case 104: // M104 + case 104: // M104: Set hot end temperature gcode_M104(); break; @@ -7247,21 +8123,27 @@ void process_next_command() { break; #endif - case 140: // M140: Set bed temp + case 140: // M140: Set bed temperature gcode_M140(); break; - case 105: // M105: Read current temperature + case 105: // M105: Report current temperature gcode_M105(); KEEPALIVE_STATE(NOT_BUSY); return; // "ok" already printed - case 109: // M109: Wait for temperature + #if ENABLED(AUTO_REPORT_TEMPERATURES) && (HAS_TEMP_HOTEND || HAS_TEMP_BED) + case 155: // M155: Set temperature auto-report interval + gcode_M155(); + break; + #endif + + case 109: // M109: Wait for hotend temperature to reach target gcode_M109(); break; #if HAS_TEMP_BED - case 190: // M190: Wait for bed heater to reach target + case 190: // M190: Wait for bed temperature to reach target gcode_M190(); break; #endif // HAS_TEMP_BED @@ -7309,30 +8191,33 @@ void process_next_command() { gcode_M81(); break; - case 82: + case 82: // M83: Set E axis normal mode (same as other axes) gcode_M82(); break; - case 83: + case 83: // M83: Set E axis relative mode gcode_M83(); break; - case 18: // (for compatibility) - case 84: // M84 + case 18: // M18 => M84 + case 84: // M84: Disable all steppers or set timeout gcode_M18_M84(); break; - case 85: // M85 + case 85: // M85: Set inactivity stepper shutdown timeout gcode_M85(); break; case 92: // M92: Set the steps-per-unit for one or more axes gcode_M92(); break; + case 114: // M114: Report current position + gcode_M114(); + break; case 115: // M115: Report capabilities gcode_M115(); break; case 117: // M117: Set LCD message text, if possible gcode_M117(); break; - case 114: // M114: Report current position - gcode_M114(); + case 119: // M119: Report endstop states + gcode_M119(); break; case 120: // M120: Enable endstops gcode_M120(); @@ -7340,9 +8225,12 @@ void process_next_command() { case 121: // M121: Disable endstops gcode_M121(); break; - case 119: // M119: Report endstop states - gcode_M119(); - break; + + #if ENABLED(HAVE_TMC2130DRIVER) + case 122: // M122: Diagnose, used to debug TMC2130 + gcode_M122(); + break; + #endif #if ENABLED(ULTIPANEL) @@ -7353,51 +8241,39 @@ void process_next_command() { #endif #if ENABLED(TEMPERATURE_UNITS_SUPPORT) - case 149: + case 149: // M149: Set temperature units gcode_M149(); break; #endif - #if ENABLED(BLINKM) + #if ENABLED(BLINKM) || ENABLED(RGB_LED) - case 150: // M150 + case 150: // M150: Set Status LED Color gcode_M150(); break; - #endif //BLINKM - - #if ENABLED(EXPERIMENTAL_I2CBUS) - - case 155: - gcode_M155(); - break; - - case 156: - gcode_M156(); - break; - - #endif //EXPERIMENTAL_I2CBUS + #endif // BLINKM #if ENABLED(MIXING_EXTRUDER) - case 163: // M163 S P set weight for a mixing extruder + case 163: // M163: Set a component weight for mixing extruder gcode_M163(); break; #if MIXING_VIRTUAL_TOOLS > 1 - case 164: // M164 S save current mix as a virtual extruder + case 164: // M164: Save current mix as a virtual extruder gcode_M164(); break; #endif #if ENABLED(DIRECT_MIXING_IN_G1) - case 165: // M165 [ABCDHI] set multiple mix weights + case 165: // M165: Set multiple mix weights gcode_M165(); break; #endif #endif - case 200: // M200 D Set filament diameter and set E axis units to cubic. (Use S0 to revert to linear units.) + case 200: // M200: Set filament diameter, E to cubic units gcode_M200(); break; - case 201: // M201 + case 201: // M201: Set max acceleration for print moves (units/s^2) gcode_M201(); break; #if 0 // Not used for Sprinter/grbl gen6 @@ -7405,229 +8281,245 @@ void process_next_command() { gcode_M202(); break; #endif - case 203: // M203 max feedrate units/sec + case 203: // M203: Set max feedrate (units/sec) gcode_M203(); break; - case 204: // M204 acclereration S normal moves T filmanent only moves + case 204: // M204: Set acceleration gcode_M204(); break; - case 205: //M205 advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk + case 205: //M205: Set advanced settings gcode_M205(); break; - case 206: // M206 additional homing offset + case 206: // M206: Set home offsets gcode_M206(); break; #if ENABLED(DELTA) - case 665: // M665 set delta configurations L R S + case 665: // M665: Set delta configurations gcode_M665(); break; #endif #if ENABLED(DELTA) || ENABLED(Z_DUAL_ENDSTOPS) - case 666: // M666 set delta / dual endstop adjustment + case 666: // M666: Set delta or dual endstop adjustment gcode_M666(); break; #endif #if ENABLED(FWRETRACT) - case 207: // M207 - Set Retract Length: S, Feedrate: F, and Z lift: Z + case 207: // M207: Set Retract Length, Feedrate, and Z lift gcode_M207(); break; - case 208: // M208 - Set Recover (unretract) Additional (!) Length: S and Feedrate: F + case 208: // M208: Set Recover (unretract) Additional Length and Feedrate gcode_M208(); break; - case 209: // M209 - Turn Automatic Retract Detection on/off: S (For slicers that don't support G10/11). Every normal extrude-only move will be classified as retract depending on the direction. + case 209: // M209: Turn Automatic Retract Detection on/off gcode_M209(); break; #endif // FWRETRACT + case 211: // M211: Enable, Disable, and/or Report software endstops + gcode_M211(); + break; + #if HOTENDS > 1 - case 218: // M218 - Set a tool offset: T X Y + case 218: // M218: Set a tool offset gcode_M218(); break; #endif - case 220: // M220 - Set Feedrate Percentage: S ("FR" on your LCD) + case 220: // M220: Set Feedrate Percentage: S ("FR" on your LCD) gcode_M220(); break; - case 221: // M221 - Set Flow Percentage: S + case 221: // M221: Set Flow Percentage gcode_M221(); break; - case 226: // M226 P S- Wait until the specified pin reaches the state required + case 226: // M226: Wait until a pin reaches a state gcode_M226(); break; #if HAS_SERVOS - case 280: // M280 - set servo position absolute. P: servo index, S: angle or microseconds + case 280: // M280: Set servo position absolute gcode_M280(); break; #endif // HAS_SERVOS #if HAS_BUZZER - case 300: // M300 - Play beep tone + case 300: // M300: Play beep tone gcode_M300(); break; #endif // HAS_BUZZER #if ENABLED(PIDTEMP) - case 301: // M301 + case 301: // M301: Set hotend PID parameters gcode_M301(); break; #endif // PIDTEMP #if ENABLED(PIDTEMPBED) - case 304: // M304 + case 304: // M304: Set bed PID parameters gcode_M304(); break; #endif // PIDTEMPBED #if defined(CHDK) || HAS_PHOTOGRAPH - case 240: // M240 Triggers a camera by emulating a Canon RC-1 : http://www.doc-diy.net/photo/rc-1_hacked/ + case 240: // M240: Trigger a camera by emulating a Canon RC-1 : http://www.doc-diy.net/photo/rc-1_hacked/ gcode_M240(); break; #endif // CHDK || PHOTOGRAPH_PIN #if HAS_LCD_CONTRAST - case 250: // M250 Set LCD contrast value: C (value 0..63) + case 250: // M250: Set LCD contrast gcode_M250(); break; #endif // HAS_LCD_CONTRAST - #if ENABLED(PREVENT_DANGEROUS_EXTRUDE) - case 302: // allow cold extrudes, or set the minimum extrude temperature + #if ENABLED(EXPERIMENTAL_I2CBUS) + + case 260: // M260: Send data to an i2c slave + gcode_M260(); + break; + + case 261: // M261: Request data from an i2c slave + gcode_M261(); + break; + + #endif // EXPERIMENTAL_I2CBUS + + #if ENABLED(PREVENT_COLD_EXTRUSION) + case 302: // M302: Allow cold extrudes (set the minimum extrude temperature) gcode_M302(); break; - #endif // PREVENT_DANGEROUS_EXTRUDE + #endif // PREVENT_COLD_EXTRUSION - case 303: // M303 PID autotune + case 303: // M303: PID autotune gcode_M303(); break; - #if ENABLED(SCARA) - case 360: // M360 SCARA Theta pos1 + #if ENABLED(MORGAN_SCARA) + case 360: // M360: SCARA Theta pos1 if (gcode_M360()) return; break; - case 361: // M361 SCARA Theta pos2 + case 361: // M361: SCARA Theta pos2 if (gcode_M361()) return; break; - case 362: // M362 SCARA Psi pos1 + case 362: // M362: SCARA Psi pos1 if (gcode_M362()) return; break; - case 363: // M363 SCARA Psi pos2 + case 363: // M363: SCARA Psi pos2 if (gcode_M363()) return; break; - case 364: // M364 SCARA Psi pos3 (90 deg to Theta) + case 364: // M364: SCARA Psi pos3 (90 deg to Theta) if (gcode_M364()) return; break; - case 365: // M365 Set SCARA scaling for X Y Z - gcode_M365(); - break; #endif // SCARA - case 400: // M400 finish all moves + case 400: // M400: Finish all moves gcode_M400(); break; #if HAS_BED_PROBE - case 401: + case 401: // M401: Deploy probe gcode_M401(); break; - case 402: + case 402: // M402: Stow probe gcode_M402(); break; #endif // HAS_BED_PROBE #if ENABLED(FILAMENT_WIDTH_SENSOR) - case 404: //M404 Enter the nominal filament width (3mm, 1.75mm ) N<3.0> or display nominal filament width + case 404: // M404: Enter the nominal filament width (3mm, 1.75mm ) N<3.0> or display nominal filament width gcode_M404(); break; - case 405: //M405 Turn on filament sensor for control + case 405: // M405: Turn on filament sensor for control gcode_M405(); break; - case 406: //M406 Turn off filament sensor for control + case 406: // M406: Turn off filament sensor for control gcode_M406(); break; - case 407: //M407 Display measured filament diameter + case 407: // M407: Display measured filament diameter gcode_M407(); break; #endif // ENABLED(FILAMENT_WIDTH_SENSOR) - #if ENABLED(MESH_BED_LEVELING) - case 420: // M420 Enable/Disable Mesh Bed Leveling + #if PLANNER_LEVELING + case 420: // M420: Enable/Disable Bed Leveling gcode_M420(); break; - case 421: // M421 Set a Mesh Bed Leveling Z coordinate + #endif + + #if ENABLED(MESH_BED_LEVELING) + case 421: // M421: Set a Mesh Bed Leveling Z coordinate gcode_M421(); break; #endif - case 428: // M428 Apply current_position to home_offset + case 428: // M428: Apply current_position to home_offset gcode_M428(); break; - case 500: // M500 Store settings in EEPROM + case 500: // M500: Store settings in EEPROM gcode_M500(); break; - case 501: // M501 Read settings from EEPROM + case 501: // M501: Read settings from EEPROM gcode_M501(); break; - case 502: // M502 Revert to default settings + case 502: // M502: Revert to default settings gcode_M502(); break; - case 503: // M503 print settings currently in memory + case 503: // M503: print settings currently in memory gcode_M503(); break; #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) - case 540: + case 540: // M540: Set abort on endstop hit for SD printing gcode_M540(); break; #endif #if HAS_BED_PROBE - case 851: + case 851: // M851: Set Z Probe Z Offset gcode_M851(); break; #endif // HAS_BED_PROBE #if ENABLED(FILAMENT_CHANGE_FEATURE) - case 600: //Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal] + case 600: // M600: Pause for filament change gcode_M600(); break; #endif // FILAMENT_CHANGE_FEATURE #if ENABLED(DUAL_X_CARRIAGE) - case 605: + case 605: // M605: Set Dual X Carriage movement mode gcode_M605(); break; #endif // DUAL_X_CARRIAGE #if ENABLED(LIN_ADVANCE) - case 905: // M905 Set advance factor. + case 905: // M905: Set advance K factor. gcode_M905(); break; #endif - case 907: // M907 Set digital trimpot motor current using axis codes. + case 907: // M907: Set digital trimpot motor current using axis codes. gcode_M907(); break; #if HAS_DIGIPOTSS || ENABLED(DAC_STEPPER_CURRENT) - case 908: // M908 Control digital trimpot directly. + case 908: // M908: Control digital trimpot directly. gcode_M908(); break; #if ENABLED(DAC_STEPPER_CURRENT) // As with Printrbot RevF - case 909: // M909 Print digipot/DAC current value + case 909: // M909: Print digipot/DAC current value gcode_M909(); break; - case 910: // M910 Commit digipot/DAC value to external EEPROM + case 910: // M910: Commit digipot/DAC value to external EEPROM gcode_M910(); break; @@ -7637,16 +8529,24 @@ void process_next_command() { #if HAS_MICROSTEPS - case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. + case 350: // M350: Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. gcode_M350(); break; - case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low. + case 351: // M351: Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low. gcode_M351(); break; #endif // HAS_MICROSTEPS + #if HAS_CASE_LIGHT + + case 355: // M355 Turn case lights on/off + gcode_M355(); + break; + + #endif // HAS_CASE_LIGHT + case 999: // M999: Restart after being Stopped gcode_M999(); break; @@ -7670,6 +8570,10 @@ ExitUnknownCommand: ok_to_send(); } +/** + * Send a "Resend: nnn" message to the host to + * indicate that a command needs to be re-sent. + */ void FlushSerialRequestResend() { //char command_queue[cmd_queue_index_r][100]="Resend:"; MYSERIAL.flush(); @@ -7678,6 +8582,15 @@ void FlushSerialRequestResend() { ok_to_send(); } +/** + * Send an "ok" message to the host, indicating + * that a command was successfully processed. + * + * If ADVANCED_OK is enabled also include: + * N Line number of the command, if any + * P Planner space remaining + * B Block queue space remaining + */ void ok_to_send() { refresh_cmd_timeout(); if (!send_ok[cmd_queue_index_r]) return; @@ -7696,21 +8609,96 @@ void ok_to_send() { SERIAL_EOL; } -void clamp_to_software_endstops(float target[3]) { - if (min_software_endstops) { - NOLESS(target[X_AXIS], sw_endstop_min[X_AXIS]); - NOLESS(target[Y_AXIS], sw_endstop_min[Y_AXIS]); - NOLESS(target[Z_AXIS], sw_endstop_min[Z_AXIS]); +#if ENABLED(min_software_endstops) || ENABLED(max_software_endstops) + + /** + * Constrain the given coordinates to the software endstops. + */ + void clamp_to_software_endstops(float target[XYZ]) { + #if ENABLED(min_software_endstops) + NOLESS(target[X_AXIS], soft_endstop_min[X_AXIS]); + NOLESS(target[Y_AXIS], soft_endstop_min[Y_AXIS]); + NOLESS(target[Z_AXIS], soft_endstop_min[Z_AXIS]); + #endif + #if ENABLED(max_software_endstops) + NOMORE(target[X_AXIS], soft_endstop_max[X_AXIS]); + NOMORE(target[Y_AXIS], soft_endstop_max[Y_AXIS]); + NOMORE(target[Z_AXIS], soft_endstop_max[Z_AXIS]); + #endif } - if (max_software_endstops) { - NOMORE(target[X_AXIS], sw_endstop_max[X_AXIS]); - NOMORE(target[Y_AXIS], sw_endstop_max[Y_AXIS]); - NOMORE(target[Z_AXIS], sw_endstop_max[Z_AXIS]); + +#endif + +#if ENABLED(AUTO_BED_LEVELING_BILINEAR) + + // Get the Z adjustment for non-linear bed leveling + float bilinear_z_offset(float cartesian[XYZ]) { + + // XY relative to the probed area + const float x = RAW_X_POSITION(cartesian[X_AXIS]) - bilinear_start[X_AXIS], + y = RAW_Y_POSITION(cartesian[Y_AXIS]) - bilinear_start[Y_AXIS]; + + // Convert to grid box units + float ratio_x = x / bilinear_grid_spacing[X_AXIS], + ratio_y = y / bilinear_grid_spacing[Y_AXIS]; + + // Whole units for the grid line indices. Constrained within bounds. + const int gridx = constrain(floor(ratio_x), 0, ABL_GRID_POINTS_X - 1), + gridy = constrain(floor(ratio_y), 0, ABL_GRID_POINTS_Y - 1), + nextx = min(gridx + 1, ABL_GRID_POINTS_X - 1), + nexty = min(gridy + 1, ABL_GRID_POINTS_Y - 1); + + // Subtract whole to get the ratio within the grid box + ratio_x -= gridx; ratio_y -= gridy; + + // Never less than 0.0. (Over 1.0 is fine due to previous contraints.) + NOLESS(ratio_x, 0); NOLESS(ratio_y, 0); + + // Z at the box corners + const float z1 = bed_level_grid[gridx][gridy], // left-front + z2 = bed_level_grid[gridx][nexty], // left-back + z3 = bed_level_grid[nextx][gridy], // right-front + z4 = bed_level_grid[nextx][nexty], // right-back + + // Bilinear interpolate + L = z1 + (z2 - z1) * ratio_y, // Linear interp. LF -> LB + R = z3 + (z4 - z3) * ratio_y, // Linear interp. RF -> RB + offset = L + ratio_x * (R - L); + + /* + static float last_offset = 0; + if (fabs(last_offset - offset) > 0.2) { + SERIAL_ECHOPGM("Sudden Shift at "); + SERIAL_ECHOPAIR("x=", x); + SERIAL_ECHOPAIR(" / ", bilinear_grid_spacing[X_AXIS]); + SERIAL_ECHOLNPAIR(" -> gridx=", gridx); + SERIAL_ECHOPAIR(" y=", y); + SERIAL_ECHOPAIR(" / ", bilinear_grid_spacing[Y_AXIS]); + SERIAL_ECHOLNPAIR(" -> gridy=", gridy); + SERIAL_ECHOPAIR(" ratio_x=", ratio_x); + SERIAL_ECHOLNPAIR(" ratio_y=", ratio_y); + SERIAL_ECHOPAIR(" z1=", z1); + SERIAL_ECHOPAIR(" z2=", z2); + SERIAL_ECHOPAIR(" z3=", z3); + SERIAL_ECHOLNPAIR(" z4=", z4); + SERIAL_ECHOPAIR(" L=", L); + SERIAL_ECHOPAIR(" R=", R); + SERIAL_ECHOLNPAIR(" offset=", offset); + } + last_offset = offset; + //*/ + + return offset; } -} + +#endif // AUTO_BED_LEVELING_BILINEAR #if ENABLED(DELTA) + /** + * Recalculate factors used for delta kinematics whenever + * settings have been changed (e.g., by M665). + */ void recalc_delta_settings(float radius, float diagonal_rod) { delta_tower1_x = -SIN_60 * (radius + DELTA_RADIUS_TRIM_TOWER_1); // front left tower delta_tower1_y = -COS_60 * (radius + DELTA_RADIUS_TRIM_TOWER_1); @@ -7723,331 +8711,544 @@ void clamp_to_software_endstops(float target[3]) { delta_diagonal_rod_2_tower_3 = sq(diagonal_rod + delta_diagonal_rod_trim_tower_3); } - void inverse_kinematics(const float in_cartesian[3]) { - - const float cartesian[3] = { - RAW_X_POSITION(in_cartesian[X_AXIS]), - RAW_Y_POSITION(in_cartesian[Y_AXIS]), - RAW_Z_POSITION(in_cartesian[Z_AXIS]) - }; - - delta[TOWER_1] = sqrt(delta_diagonal_rod_2_tower_1 - - sq(delta_tower1_x - cartesian[X_AXIS]) - - sq(delta_tower1_y - cartesian[Y_AXIS]) - ) + cartesian[Z_AXIS]; - delta[TOWER_2] = sqrt(delta_diagonal_rod_2_tower_2 - - sq(delta_tower2_x - cartesian[X_AXIS]) - - sq(delta_tower2_y - cartesian[Y_AXIS]) - ) + cartesian[Z_AXIS]; - delta[TOWER_3] = sqrt(delta_diagonal_rod_2_tower_3 - - sq(delta_tower3_x - cartesian[X_AXIS]) - - sq(delta_tower3_y - cartesian[Y_AXIS]) - ) + cartesian[Z_AXIS]; + #if ENABLED(DELTA_FAST_SQRT) /** - SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]); - SERIAL_ECHOPGM(" y="); SERIAL_ECHO(cartesian[Y_AXIS]); - SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(cartesian[Z_AXIS]); + * Fast inverse sqrt from Quake III Arena + * See: https://en.wikipedia.org/wiki/Fast_inverse_square_root + */ + float Q_rsqrt(float number) { + long i; + float x2, y; + const float threehalfs = 1.5f; + x2 = number * 0.5f; + y = number; + i = * ( long * ) &y; // evil floating point bit level hacking + i = 0x5f3759df - ( i >> 1 ); // what the f***? + y = * ( float * ) &i; + y = y * ( threehalfs - ( x2 * y * y ) ); // 1st iteration + // y = y * ( threehalfs - ( x2 * y * y ) ); // 2nd iteration, this can be removed + return y; + } - SERIAL_ECHOPGM("delta a="); SERIAL_ECHO(delta[TOWER_1]); - SERIAL_ECHOPGM(" b="); SERIAL_ECHO(delta[TOWER_2]); - SERIAL_ECHOPGM(" c="); SERIAL_ECHOLN(delta[TOWER_3]); - */ + #define _SQRT(n) (1.0f / Q_rsqrt(n)) + + #else + + #define _SQRT(n) sqrt(n) + + #endif + + /** + * Delta Inverse Kinematics + * + * Calculate the tower positions for a given logical + * position, storing the result in the delta[] array. + * + * This is an expensive calculation, requiring 3 square + * roots per segmented linear move, and strains the limits + * of a Mega2560 with a Graphical Display. + * + * Suggested optimizations include: + * + * - Disable the home_offset (M206) and/or position_shift (G92) + * features to remove up to 12 float additions. + * + * - Use a fast-inverse-sqrt function and add the reciprocal. + * (see above) + */ + + // Macro to obtain the Z position of an individual tower + #define DELTA_Z(T) raw[Z_AXIS] + _SQRT( \ + delta_diagonal_rod_2_tower_##T - HYPOT2( \ + delta_tower##T##_x - raw[X_AXIS], \ + delta_tower##T##_y - raw[Y_AXIS] \ + ) \ + ) + + #define DELTA_RAW_IK() do { \ + delta[A_AXIS] = DELTA_Z(1); \ + delta[B_AXIS] = DELTA_Z(2); \ + delta[C_AXIS] = DELTA_Z(3); \ + } while(0) + + #define DELTA_LOGICAL_IK() do { \ + const float raw[XYZ] = { \ + RAW_X_POSITION(logical[X_AXIS]), \ + RAW_Y_POSITION(logical[Y_AXIS]), \ + RAW_Z_POSITION(logical[Z_AXIS]) \ + }; \ + DELTA_RAW_IK(); \ + } while(0) + + #define DELTA_DEBUG() do { \ + SERIAL_ECHOPAIR("cartesian X:", raw[X_AXIS]); \ + SERIAL_ECHOPAIR(" Y:", raw[Y_AXIS]); \ + SERIAL_ECHOLNPAIR(" Z:", raw[Z_AXIS]); \ + SERIAL_ECHOPAIR("delta A:", delta[A_AXIS]); \ + SERIAL_ECHOPAIR(" B:", delta[B_AXIS]); \ + SERIAL_ECHOLNPAIR(" C:", delta[C_AXIS]); \ + } while(0) + + void inverse_kinematics(const float logical[XYZ]) { + DELTA_LOGICAL_IK(); + // DELTA_DEBUG(); } + /** + * Calculate the highest Z position where the + * effector has the full range of XY motion. + */ float delta_safe_distance_from_top() { - float cartesian[3] = { + float cartesian[XYZ] = { LOGICAL_X_POSITION(0), LOGICAL_Y_POSITION(0), LOGICAL_Z_POSITION(0) }; inverse_kinematics(cartesian); - float distance = delta[TOWER_3]; + float distance = delta[A_AXIS]; cartesian[Y_AXIS] = LOGICAL_Y_POSITION(DELTA_PRINTABLE_RADIUS); inverse_kinematics(cartesian); - return abs(distance - delta[TOWER_3]); + return abs(distance - delta[A_AXIS]); } + /** + * Delta Forward Kinematics + * + * See the Wikipedia article "Trilateration" + * https://en.wikipedia.org/wiki/Trilateration + * + * Establish a new coordinate system in the plane of the + * three carriage points. This system has its origin at + * tower1, with tower2 on the X axis. Tower3 is in the X-Y + * plane with a Z component of zero. + * We will define unit vectors in this coordinate system + * in our original coordinate system. Then when we calculate + * the Xnew, Ynew and Znew values, we can translate back into + * the original system by moving along those unit vectors + * by the corresponding values. + * + * Variable names matched to Marlin, c-version, and avoid the + * use of any vector library. + * + * by Andreas Hardtung 2016-06-07 + * based on a Java function from "Delta Robot Kinematics V3" + * by Steve Graves + * + * The result is stored in the cartes[] array. + */ void forward_kinematics_DELTA(float z1, float z2, float z3) { - //As discussed in Wikipedia "Trilateration" - //we are establishing a new coordinate - //system in the plane of the three carriage points. - //This system will have the origin at tower1 and - //tower2 is on the x axis. tower3 is in the X-Y - //plane with a Z component of zero. We will define unit - //vectors in this coordinate system in our original - //coordinate system. Then when we calculate the - //Xnew, Ynew and Znew values, we can translate back into - //the original system by moving along those unit vectors - //by the corresponding values. - // https://en.wikipedia.org/wiki/Trilateration - - // Variable names matched to Marlin, c-version - // and avoiding a vector library - // by Andreas Hardtung 2016-06-7 - // based on a Java function from - // "Delta Robot Kinematics by Steve Graves" V3 - - // Result is in cartesian_position[]. - - //Create a vector in old coordinates along x axis of new coordinate + // Create a vector in old coordinates along x axis of new coordinate float p12[3] = { delta_tower2_x - delta_tower1_x, delta_tower2_y - delta_tower1_y, z2 - z1 }; - //Get the Magnitude of vector. - float d = sqrt( p12[0]*p12[0] + p12[1]*p12[1] + p12[2]*p12[2] ); + // Get the Magnitude of vector. + float d = sqrt( sq(p12[0]) + sq(p12[1]) + sq(p12[2]) ); - //Create unit vector by dividing by magnitude. - float ex[3] = { p12[0]/d, p12[1]/d, p12[2]/d }; + // Create unit vector by dividing by magnitude. + float ex[3] = { p12[0] / d, p12[1] / d, p12[2] / d }; - //Now find vector from the origin of the new system to the third point. + // Get the vector from the origin of the new system to the third point. float p13[3] = { delta_tower3_x - delta_tower1_x, delta_tower3_y - delta_tower1_y, z3 - z1 }; - //Now use dot product to find the component of this vector on the X axis. - float i = ex[0]*p13[0] + ex[1]*p13[1] + ex[2]*p13[2]; + // Use the dot product to find the component of this vector on the X axis. + float i = ex[0] * p13[0] + ex[1] * p13[1] + ex[2] * p13[2]; - //Now create a vector along the x axis that represents the x component of p13. - float iex[3] = { ex[0]*i, ex[1]*i, ex[2]*i }; + // Create a vector along the x axis that represents the x component of p13. + float iex[3] = { ex[0] * i, ex[1] * i, ex[2] * i }; - //Now subtract the X component away from the original vector leaving only the Y component. We use the - //variable that will be the unit vector after we scale it. - float ey[3] = { p13[0] - iex[0], p13[1] - iex[1], p13[2] - iex[2]}; + // Subtract the X component from the original vector leaving only Y. We use the + // variable that will be the unit vector after we scale it. + float ey[3] = { p13[0] - iex[0], p13[1] - iex[1], p13[2] - iex[2] }; - //The magnitude of Y component - float j = sqrt(sq(ey[0]) + sq(ey[1]) + sq(ey[2])); + // The magnitude of Y component + float j = sqrt( sq(ey[0]) + sq(ey[1]) + sq(ey[2]) ); - //Now make vector a unit vector + // Convert to a unit vector ey[0] /= j; ey[1] /= j; ey[2] /= j; - //The cross product of the unit x and y is the unit z - //float[] ez = vectorCrossProd(ex, ey); - float ez[3] = { ex[1]*ey[2] - ex[2]*ey[1], ex[2]*ey[0] - ex[0]*ey[2], ex[0]*ey[1] - ex[1]*ey[0] }; + // The cross product of the unit x and y is the unit z + // float[] ez = vectorCrossProd(ex, ey); + float ez[3] = { + ex[1] * ey[2] - ex[2] * ey[1], + ex[2] * ey[0] - ex[0] * ey[2], + ex[0] * ey[1] - ex[1] * ey[0] + }; - //Now we have the d, i and j values defined in Wikipedia. - //We can plug them into the equations defined in - //Wikipedia for Xnew, Ynew and Znew - float Xnew = (delta_diagonal_rod_2_tower_1 - delta_diagonal_rod_2_tower_2 + d*d)/(d*2); - float Ynew = ((delta_diagonal_rod_2_tower_1 - delta_diagonal_rod_2_tower_3 + i*i + j*j)/2 - i*Xnew) /j; - float Znew = sqrt(delta_diagonal_rod_2_tower_1 - Xnew*Xnew - Ynew*Ynew); + // We now have the d, i and j values defined in Wikipedia. + // Plug them into the equations defined in Wikipedia for Xnew, Ynew and Znew + float Xnew = (delta_diagonal_rod_2_tower_1 - delta_diagonal_rod_2_tower_2 + sq(d)) / (d * 2), + Ynew = ((delta_diagonal_rod_2_tower_1 - delta_diagonal_rod_2_tower_3 + HYPOT2(i, j)) / 2 - i * Xnew) / j, + Znew = sqrt(delta_diagonal_rod_2_tower_1 - HYPOT2(Xnew, Ynew)); - //Now we can start from the origin in the old coords and - //add vectors in the old coords that represent the - //Xnew, Ynew and Znew to find the point in the old system - cartesian_position[X_AXIS] = delta_tower1_x + ex[0]*Xnew + ey[0]*Ynew - ez[0]*Znew; - cartesian_position[Y_AXIS] = delta_tower1_y + ex[1]*Xnew + ey[1]*Ynew - ez[1]*Znew; - cartesian_position[Z_AXIS] = z1 + ex[2]*Xnew + ey[2]*Ynew - ez[2]*Znew; - }; - - void forward_kinematics_DELTA(float point[3]) { - forward_kinematics_DELTA(point[X_AXIS], point[Y_AXIS], point[Z_AXIS]); + // Start from the origin of the old coordinates and add vectors in the + // old coords that represent the Xnew, Ynew and Znew to find the point + // in the old system. + cartes[X_AXIS] = delta_tower1_x + ex[0] * Xnew + ey[0] * Ynew - ez[0] * Znew; + cartes[Y_AXIS] = delta_tower1_y + ex[1] * Xnew + ey[1] * Ynew - ez[1] * Znew; + cartes[Z_AXIS] = z1 + ex[2] * Xnew + ey[2] * Ynew - ez[2] * Znew; } - void set_cartesian_from_steppers() { - forward_kinematics_DELTA(stepper.get_axis_position_mm(X_AXIS), - stepper.get_axis_position_mm(Y_AXIS), - stepper.get_axis_position_mm(Z_AXIS)); + void forward_kinematics_DELTA(float point[ABC]) { + forward_kinematics_DELTA(point[A_AXIS], point[B_AXIS], point[C_AXIS]); } - #if ENABLED(AUTO_BED_LEVELING_FEATURE) - - // Adjust print surface height by linear interpolation over the bed_level array. - void adjust_delta(float cartesian[3]) { - if (delta_grid_spacing[0] == 0 || delta_grid_spacing[1] == 0) return; // G29 not done! - - int half = (AUTO_BED_LEVELING_GRID_POINTS - 1) / 2; - float h1 = 0.001 - half, h2 = half - 0.001, - grid_x = max(h1, min(h2, RAW_X_POSITION(cartesian[X_AXIS]) / delta_grid_spacing[0])), - grid_y = max(h1, min(h2, RAW_Y_POSITION(cartesian[Y_AXIS]) / delta_grid_spacing[1])); - int floor_x = floor(grid_x), floor_y = floor(grid_y); - float ratio_x = grid_x - floor_x, ratio_y = grid_y - floor_y, - z1 = bed_level[floor_x + half][floor_y + half], - z2 = bed_level[floor_x + half][floor_y + half + 1], - z3 = bed_level[floor_x + half + 1][floor_y + half], - z4 = bed_level[floor_x + half + 1][floor_y + half + 1], - left = (1 - ratio_y) * z1 + ratio_y * z2, - right = (1 - ratio_y) * z3 + ratio_y * z4, - offset = (1 - ratio_x) * left + ratio_x * right; - - delta[X_AXIS] += offset; - delta[Y_AXIS] += offset; - delta[Z_AXIS] += offset; - - /** - SERIAL_ECHOPGM("grid_x="); SERIAL_ECHO(grid_x); - SERIAL_ECHOPGM(" grid_y="); SERIAL_ECHO(grid_y); - SERIAL_ECHOPGM(" floor_x="); SERIAL_ECHO(floor_x); - SERIAL_ECHOPGM(" floor_y="); SERIAL_ECHO(floor_y); - SERIAL_ECHOPGM(" ratio_x="); SERIAL_ECHO(ratio_x); - SERIAL_ECHOPGM(" ratio_y="); SERIAL_ECHO(ratio_y); - SERIAL_ECHOPGM(" z1="); SERIAL_ECHO(z1); - SERIAL_ECHOPGM(" z2="); SERIAL_ECHO(z2); - SERIAL_ECHOPGM(" z3="); SERIAL_ECHO(z3); - SERIAL_ECHOPGM(" z4="); SERIAL_ECHO(z4); - SERIAL_ECHOPGM(" left="); SERIAL_ECHO(left); - SERIAL_ECHOPGM(" right="); SERIAL_ECHO(right); - SERIAL_ECHOPGM(" offset="); SERIAL_ECHOLN(offset); - */ - } - #endif // AUTO_BED_LEVELING_FEATURE - #endif // DELTA -void set_current_from_steppers_for_axis(AxisEnum axis) { +/** + * Get the stepper positions in the cartes[] array. + * Forward kinematics are applied for DELTA and SCARA. + * + * The result is in the current coordinate space with + * leveling applied. The coordinates need to be run through + * unapply_leveling to obtain the "ideal" coordinates + * suitable for current_position, etc. + */ +void get_cartesian_from_steppers() { #if ENABLED(DELTA) - set_cartesian_from_steppers(); - current_position[axis] = LOGICAL_POSITION(cartesian_position[axis], axis); - #elif ENABLED(AUTO_BED_LEVELING_FEATURE) - vector_3 pos = planner.adjusted_position(); - current_position[axis] = axis == X_AXIS ? pos.x : axis == Y_AXIS ? pos.y : pos.z; + forward_kinematics_DELTA( + stepper.get_axis_position_mm(A_AXIS), + stepper.get_axis_position_mm(B_AXIS), + stepper.get_axis_position_mm(C_AXIS) + ); + cartes[X_AXIS] += LOGICAL_X_POSITION(0); + cartes[Y_AXIS] += LOGICAL_Y_POSITION(0); + cartes[Z_AXIS] += LOGICAL_Z_POSITION(0); + #elif IS_SCARA + forward_kinematics_SCARA( + stepper.get_axis_position_degrees(A_AXIS), + stepper.get_axis_position_degrees(B_AXIS) + ); + cartes[X_AXIS] += LOGICAL_X_POSITION(0); + cartes[Y_AXIS] += LOGICAL_Y_POSITION(0); + cartes[Z_AXIS] = stepper.get_axis_position_mm(Z_AXIS); #else - current_position[axis] = stepper.get_axis_position_mm(axis); // CORE handled transparently + cartes[X_AXIS] = stepper.get_axis_position_mm(X_AXIS); + cartes[Y_AXIS] = stepper.get_axis_position_mm(Y_AXIS); + cartes[Z_AXIS] = stepper.get_axis_position_mm(Z_AXIS); #endif } +/** + * Set the current_position for an axis based on + * the stepper positions, removing any leveling that + * may have been applied. + */ +void set_current_from_steppers_for_axis(const AxisEnum axis) { + get_cartesian_from_steppers(); + #if PLANNER_LEVELING + planner.unapply_leveling(cartes); + #endif + if (axis == ALL_AXES) + memcpy(current_position, cartes, sizeof(cartes)); + else + current_position[axis] = cartes[axis]; +} + #if ENABLED(MESH_BED_LEVELING) -// This function is used to split lines on mesh borders so each segment is only part of one mesh area -void mesh_line_to_destination(float fr_mm_m, uint8_t x_splits = 0xff, uint8_t y_splits = 0xff) { - int cx1 = mbl.cell_index_x(RAW_CURRENT_POSITION(X_AXIS)), - cy1 = mbl.cell_index_y(RAW_CURRENT_POSITION(Y_AXIS)), - cx2 = mbl.cell_index_x(RAW_X_POSITION(destination[X_AXIS])), - cy2 = mbl.cell_index_y(RAW_Y_POSITION(destination[Y_AXIS])); - NOMORE(cx1, MESH_NUM_X_POINTS - 2); - NOMORE(cy1, MESH_NUM_Y_POINTS - 2); - NOMORE(cx2, MESH_NUM_X_POINTS - 2); - NOMORE(cy2, MESH_NUM_Y_POINTS - 2); + /** + * Prepare a mesh-leveled linear move in a Cartesian setup, + * splitting the move where it crosses mesh borders. + */ + void mesh_line_to_destination(float fr_mm_s, uint8_t x_splits = 0xff, uint8_t y_splits = 0xff) { + int cx1 = mbl.cell_index_x(RAW_CURRENT_POSITION(X_AXIS)), + cy1 = mbl.cell_index_y(RAW_CURRENT_POSITION(Y_AXIS)), + cx2 = mbl.cell_index_x(RAW_X_POSITION(destination[X_AXIS])), + cy2 = mbl.cell_index_y(RAW_Y_POSITION(destination[Y_AXIS])); + NOMORE(cx1, MESH_NUM_X_POINTS - 2); + NOMORE(cy1, MESH_NUM_Y_POINTS - 2); + NOMORE(cx2, MESH_NUM_X_POINTS - 2); + NOMORE(cy2, MESH_NUM_Y_POINTS - 2); - if (cx1 == cx2 && cy1 == cy2) { - // Start and end on same mesh square - line_to_destination(fr_mm_m); - set_current_to_destination(); - return; + if (cx1 == cx2 && cy1 == cy2) { + // Start and end on same mesh square + line_to_destination(fr_mm_s); + set_current_to_destination(); + return; + } + + #define MBL_SEGMENT_END(A) (current_position[A ##_AXIS] + (destination[A ##_AXIS] - current_position[A ##_AXIS]) * normalized_dist) + + float normalized_dist, end[XYZE]; + + // Split at the left/front border of the right/top square + int8_t gcx = max(cx1, cx2), gcy = max(cy1, cy2); + if (cx2 != cx1 && TEST(x_splits, gcx)) { + memcpy(end, destination, sizeof(end)); + destination[X_AXIS] = LOGICAL_X_POSITION(mbl.get_probe_x(gcx)); + normalized_dist = (destination[X_AXIS] - current_position[X_AXIS]) / (end[X_AXIS] - current_position[X_AXIS]); + destination[Y_AXIS] = MBL_SEGMENT_END(Y); + CBI(x_splits, gcx); + } + else if (cy2 != cy1 && TEST(y_splits, gcy)) { + memcpy(end, destination, sizeof(end)); + destination[Y_AXIS] = LOGICAL_Y_POSITION(mbl.get_probe_y(gcy)); + normalized_dist = (destination[Y_AXIS] - current_position[Y_AXIS]) / (end[Y_AXIS] - current_position[Y_AXIS]); + destination[X_AXIS] = MBL_SEGMENT_END(X); + CBI(y_splits, gcy); + } + else { + // Already split on a border + line_to_destination(fr_mm_s); + set_current_to_destination(); + return; + } + + destination[Z_AXIS] = MBL_SEGMENT_END(Z); + destination[E_AXIS] = MBL_SEGMENT_END(E); + + // Do the split and look for more borders + mesh_line_to_destination(fr_mm_s, x_splits, y_splits); + + // Restore destination from stack + memcpy(destination, end, sizeof(end)); + mesh_line_to_destination(fr_mm_s, x_splits, y_splits); } - #define MBL_SEGMENT_END(A) (current_position[A ##_AXIS] + (destination[A ##_AXIS] - current_position[A ##_AXIS]) * normalized_dist) +#elif ENABLED(AUTO_BED_LEVELING_BILINEAR) && !IS_KINEMATIC - float normalized_dist, end[NUM_AXIS]; + #define CELL_INDEX(A,V) ((RAW_##A##_POSITION(V) - bilinear_start[A##_AXIS]) / bilinear_grid_spacing[A##_AXIS]) - // Split at the left/front border of the right/top square - int8_t gcx = max(cx1, cx2), gcy = max(cy1, cy2); - if (cx2 != cx1 && TEST(x_splits, gcx)) { - memcpy(end, destination, sizeof(end)); - destination[X_AXIS] = LOGICAL_X_POSITION(mbl.get_probe_x(gcx)); - normalized_dist = (destination[X_AXIS] - current_position[X_AXIS]) / (end[X_AXIS] - current_position[X_AXIS]); - destination[Y_AXIS] = MBL_SEGMENT_END(Y); - CBI(x_splits, gcx); - } - else if (cy2 != cy1 && TEST(y_splits, gcy)) { - memcpy(end, destination, sizeof(end)); - destination[Y_AXIS] = LOGICAL_Y_POSITION(mbl.get_probe_y(gcy)); - normalized_dist = (destination[Y_AXIS] - current_position[Y_AXIS]) / (end[Y_AXIS] - current_position[Y_AXIS]); - destination[X_AXIS] = MBL_SEGMENT_END(X); - CBI(y_splits, gcy); - } - else { - // Already split on a border - line_to_destination(fr_mm_m); - set_current_to_destination(); - return; + /** + * Prepare a bilinear-leveled linear move on Cartesian, + * splitting the move where it crosses grid borders. + */ + void bilinear_line_to_destination(float fr_mm_s, uint16_t x_splits = 0xFFFF, uint16_t y_splits = 0xFFFF) { + int cx1 = CELL_INDEX(X, current_position[X_AXIS]), + cy1 = CELL_INDEX(Y, current_position[Y_AXIS]), + cx2 = CELL_INDEX(X, destination[X_AXIS]), + cy2 = CELL_INDEX(Y, destination[Y_AXIS]); + cx1 = constrain(cx1, 0, ABL_GRID_POINTS_X - 2); + cy1 = constrain(cy1, 0, ABL_GRID_POINTS_Y - 2); + cx2 = constrain(cx2, 0, ABL_GRID_POINTS_X - 2); + cy2 = constrain(cy2, 0, ABL_GRID_POINTS_Y - 2); + + if (cx1 == cx2 && cy1 == cy2) { + // Start and end on same mesh square + line_to_destination(fr_mm_s); + set_current_to_destination(); + return; + } + + #define LINE_SEGMENT_END(A) (current_position[A ##_AXIS] + (destination[A ##_AXIS] - current_position[A ##_AXIS]) * normalized_dist) + + float normalized_dist, end[XYZE]; + + // Split at the left/front border of the right/top square + int8_t gcx = max(cx1, cx2), gcy = max(cy1, cy2); + if (cx2 != cx1 && TEST(x_splits, gcx)) { + memcpy(end, destination, sizeof(end)); + destination[X_AXIS] = LOGICAL_X_POSITION(bilinear_start[X_AXIS] + bilinear_grid_spacing[X_AXIS] * gcx); + normalized_dist = (destination[X_AXIS] - current_position[X_AXIS]) / (end[X_AXIS] - current_position[X_AXIS]); + destination[Y_AXIS] = LINE_SEGMENT_END(Y); + CBI(x_splits, gcx); + } + else if (cy2 != cy1 && TEST(y_splits, gcy)) { + memcpy(end, destination, sizeof(end)); + destination[Y_AXIS] = LOGICAL_Y_POSITION(bilinear_start[Y_AXIS] + bilinear_grid_spacing[Y_AXIS] * gcy); + normalized_dist = (destination[Y_AXIS] - current_position[Y_AXIS]) / (end[Y_AXIS] - current_position[Y_AXIS]); + destination[X_AXIS] = LINE_SEGMENT_END(X); + CBI(y_splits, gcy); + } + else { + // Already split on a border + line_to_destination(fr_mm_s); + set_current_to_destination(); + return; + } + + destination[Z_AXIS] = LINE_SEGMENT_END(Z); + destination[E_AXIS] = LINE_SEGMENT_END(E); + + // Do the split and look for more borders + bilinear_line_to_destination(fr_mm_s, x_splits, y_splits); + + // Restore destination from stack + memcpy(destination, end, sizeof(end)); + bilinear_line_to_destination(fr_mm_s, x_splits, y_splits); } - destination[Z_AXIS] = MBL_SEGMENT_END(Z); - destination[E_AXIS] = MBL_SEGMENT_END(E); +#endif // AUTO_BED_LEVELING_BILINEAR - // Do the split and look for more borders - mesh_line_to_destination(fr_mm_m, x_splits, y_splits); +#if IS_KINEMATIC - // Restore destination from stack - memcpy(destination, end, sizeof(end)); - mesh_line_to_destination(fr_mm_m, x_splits, y_splits); -} -#endif // MESH_BED_LEVELING + /** + * Prepare a linear move in a DELTA or SCARA setup. + * + * This calls planner.buffer_line several times, adding + * small incremental moves for DELTA or SCARA. + */ + inline bool prepare_kinematic_move_to(float ltarget[NUM_AXIS]) { -#if ENABLED(DELTA) || ENABLED(SCARA) + // Get the top feedrate of the move in the XY plane + float _feedrate_mm_s = MMS_SCALED(feedrate_mm_s); - inline bool prepare_kinematic_move_to(float target[NUM_AXIS]) { + // If the move is only in Z/E don't split up the move + if (ltarget[X_AXIS] == current_position[X_AXIS] && ltarget[Y_AXIS] == current_position[Y_AXIS]) { + planner.buffer_line_kinematic(ltarget, _feedrate_mm_s, active_extruder); + return true; + } + + // Get the cartesian distances moved in XYZE float difference[NUM_AXIS]; - LOOP_XYZE(i) difference[i] = target[i] - current_position[i]; + LOOP_XYZE(i) difference[i] = ltarget[i] - current_position[i]; + // Get the linear distance in XYZ float cartesian_mm = sqrt(sq(difference[X_AXIS]) + sq(difference[Y_AXIS]) + sq(difference[Z_AXIS])); - if (cartesian_mm < 0.000001) cartesian_mm = abs(difference[E_AXIS]); - if (cartesian_mm < 0.000001) return false; - float _feedrate_mm_s = MMM_TO_MMS_SCALED(feedrate_mm_m); + + // If the move is very short, check the E move distance + if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = abs(difference[E_AXIS]); + + // No E move either? Game over. + if (UNEAR_ZERO(cartesian_mm)) return false; + + // Minimum number of seconds to move the given distance float seconds = cartesian_mm / _feedrate_mm_s; - int steps = max(1, int(delta_segments_per_second * seconds)); - float inv_steps = 1.0/steps; - // SERIAL_ECHOPGM("mm="); SERIAL_ECHO(cartesian_mm); - // SERIAL_ECHOPGM(" seconds="); SERIAL_ECHO(seconds); - // SERIAL_ECHOPGM(" steps="); SERIAL_ECHOLN(steps); + // The number of segments-per-second times the duration + // gives the number of segments + uint16_t segments = delta_segments_per_second * seconds; - for (int s = 1; s <= steps; s++) { + // For SCARA minimum segment size is 0.5mm + #if IS_SCARA + NOMORE(segments, cartesian_mm * 2); + #endif - float fraction = float(s) * inv_steps; + // At least one segment is required + NOLESS(segments, 1); - LOOP_XYZE(i) - target[i] = current_position[i] + difference[i] * fraction; + // The approximate length of each segment + float segment_distance[XYZE] = { + difference[X_AXIS] / segments, + difference[Y_AXIS] / segments, + difference[Z_AXIS] / segments, + difference[E_AXIS] / segments + }; - inverse_kinematics(target); + // SERIAL_ECHOPAIR("mm=", cartesian_mm); + // SERIAL_ECHOPAIR(" seconds=", seconds); + // SERIAL_ECHOLNPAIR(" segments=", segments); - #if ENABLED(DELTA) && ENABLED(AUTO_BED_LEVELING_FEATURE) - if (!bed_leveling_in_progress) adjust_delta(target); + // Drop one segment so the last move is to the exact target. + // If there's only 1 segment, loops will be skipped entirely. + --segments; + + // Using "raw" coordinates saves 6 float subtractions + // per segment, saving valuable CPU cycles + + #if ENABLED(USE_RAW_KINEMATICS) + + // Get the raw current position as starting point + float raw[XYZE] = { + RAW_CURRENT_POSITION(X_AXIS), + RAW_CURRENT_POSITION(Y_AXIS), + RAW_CURRENT_POSITION(Z_AXIS), + current_position[E_AXIS] + }; + + #define DELTA_VAR raw + + // Delta can inline its kinematics + #if ENABLED(DELTA) + #define DELTA_IK() DELTA_RAW_IK() + #else + #define DELTA_IK() inverse_kinematics(raw) #endif - //DEBUG_POS("prepare_kinematic_move_to", target); - //DEBUG_POS("prepare_kinematic_move_to", delta); + #else - planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], target[E_AXIS], _feedrate_mm_s, active_extruder); - } - return true; - } + // Get the logical current position as starting point + float logical[XYZE]; + memcpy(logical, current_position, sizeof(logical)); -#endif // DELTA || SCARA + #define DELTA_VAR logical -#if ENABLED(DUAL_X_CARRIAGE) + // Delta can inline its kinematics + #if ENABLED(DELTA) + #define DELTA_IK() DELTA_LOGICAL_IK() + #else + #define DELTA_IK() inverse_kinematics(logical) + #endif - inline bool prepare_move_to_destination_dualx() { - if (active_extruder_parked) { - if (dual_x_carriage_mode == DXC_DUPLICATION_MODE && active_extruder == 0) { - // move duplicate extruder into correct duplication position. - planner.set_position_mm( - LOGICAL_X_POSITION(inactive_extruder_x_pos), - current_position[Y_AXIS], - current_position[Z_AXIS], - current_position[E_AXIS] - ); - planner.buffer_line(current_position[X_AXIS] + duplicate_extruder_x_offset, - current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], planner.max_feedrate_mm_s[X_AXIS], 1); - SYNC_PLAN_POSITION_KINEMATIC(); - stepper.synchronize(); - extruder_duplication_enabled = true; - active_extruder_parked = false; + #endif + + #if ENABLED(USE_DELTA_IK_INTERPOLATION) + + // Only interpolate XYZ. Advance E normally. + #define DELTA_NEXT(ADDEND) LOOP_XYZ(i) DELTA_VAR[i] += ADDEND; + + // Get the starting delta if interpolation is possible + if (segments >= 2) { + DELTA_IK(); + ADJUST_DELTA(DELTA_VAR); // Adjust Z if bed leveling is enabled } - else if (dual_x_carriage_mode == DXC_AUTO_PARK_MODE) { // handle unparking of head - if (current_position[E_AXIS] == destination[E_AXIS]) { - // This is a travel move (with no extrusion) - // Skip it, but keep track of the current position - // (so it can be used as the start of the next non-travel move) - if (delayed_move_time != 0xFFFFFFFFUL) { - set_current_to_destination(); - NOLESS(raised_parked_position[Z_AXIS], destination[Z_AXIS]); - delayed_move_time = millis(); - return false; - } + + // Loop using decrement + for (uint16_t s = segments + 1; --s;) { + // Are there at least 2 moves left? + if (s >= 2) { + // Save the previous delta for interpolation + float prev_delta[ABC] = { delta[A_AXIS], delta[B_AXIS], delta[C_AXIS] }; + + // Get the delta 2 segments ahead (rather than the next) + DELTA_NEXT(segment_distance[i] + segment_distance[i]); + + // Advance E normally + DELTA_VAR[E_AXIS] += segment_distance[E_AXIS]; + + // Get the exact delta for the move after this + DELTA_IK(); + ADJUST_DELTA(DELTA_VAR); // Adjust Z if bed leveling is enabled + + // Move to the interpolated delta position first + planner.buffer_line( + (prev_delta[A_AXIS] + delta[A_AXIS]) * 0.5, + (prev_delta[B_AXIS] + delta[B_AXIS]) * 0.5, + (prev_delta[C_AXIS] + delta[C_AXIS]) * 0.5, + DELTA_VAR[E_AXIS], _feedrate_mm_s, active_extruder + ); + + // Advance E once more for the next move + DELTA_VAR[E_AXIS] += segment_distance[E_AXIS]; + + // Do an extra decrement of the loop + --s; } - delayed_move_time = 0; - // unpark extruder: 1) raise, 2) move into starting XY position, 3) lower - planner.buffer_line(raised_parked_position[X_AXIS], raised_parked_position[Y_AXIS], raised_parked_position[Z_AXIS], current_position[E_AXIS], planner.max_feedrate_mm_s[Z_AXIS], active_extruder); - planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], raised_parked_position[Z_AXIS], current_position[E_AXIS], PLANNER_XY_FEEDRATE(), active_extruder); - planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], planner.max_feedrate_mm_s[Z_AXIS], active_extruder); - active_extruder_parked = false; + else { + // Get the last segment delta. (Used when segments is odd) + DELTA_NEXT(segment_distance[i]); + DELTA_VAR[E_AXIS] += segment_distance[E_AXIS]; + DELTA_IK(); + ADJUST_DELTA(DELTA_VAR); // Adjust Z if bed leveling is enabled + } + + // Move to the non-interpolated position + planner.buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], DELTA_VAR[E_AXIS], _feedrate_mm_s, active_extruder); } - } + + #else + + #define DELTA_NEXT(ADDEND) LOOP_XYZE(i) DELTA_VAR[i] += ADDEND; + + // For non-interpolated delta calculate every segment + for (uint16_t s = segments + 1; --s;) { + DELTA_NEXT(segment_distance[i]); + planner.buffer_line_kinematic(DELTA_VAR, _feedrate_mm_s, active_extruder); + } + + #endif + + // Since segment_distance is only approximate, + // the final move must be to the exact destination. + planner.buffer_line_kinematic(ltarget, _feedrate_mm_s, active_extruder); return true; } -#endif // DUAL_X_CARRIAGE - -#if DISABLED(DELTA) && DISABLED(SCARA) +#else // !IS_KINEMATIC + /** + * Prepare a linear move in a Cartesian setup. + * If Mesh Bed Leveling is enabled, perform a mesh move. + */ inline bool prepare_move_to_destination_cartesian() { // Do not use feedrate_percentage for E or Z only moves if (current_position[X_AXIS] == destination[X_AXIS] && current_position[Y_AXIS] == destination[Y_AXIS]) { @@ -8056,56 +9257,118 @@ void mesh_line_to_destination(float fr_mm_m, uint8_t x_splits = 0xff, uint8_t y_ else { #if ENABLED(MESH_BED_LEVELING) if (mbl.active()) { - mesh_line_to_destination(MMM_SCALED(feedrate_mm_m)); + mesh_line_to_destination(MMS_SCALED(feedrate_mm_s)); + return false; + } + else + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + if (planner.abl_enabled) { + bilinear_line_to_destination(MMS_SCALED(feedrate_mm_s)); return false; } else #endif - line_to_destination(MMM_SCALED(feedrate_mm_m)); + line_to_destination(MMS_SCALED(feedrate_mm_s)); } return true; } -#endif // !DELTA && !SCARA +#endif // !IS_KINEMATIC -#if ENABLED(PREVENT_DANGEROUS_EXTRUDE) +#if ENABLED(DUAL_X_CARRIAGE) - inline void prevent_dangerous_extrude(float& curr_e, float& dest_e) { - if (DEBUGGING(DRYRUN)) return; - float de = dest_e - curr_e; - if (de) { - if (thermalManager.tooColdToExtrude(active_extruder)) { - curr_e = dest_e; // Behave as if the move really took place, but ignore E part - SERIAL_ECHO_START; - SERIAL_ECHOLNPGM(MSG_ERR_COLD_EXTRUDE_STOP); + /** + * Prepare a linear move in a dual X axis setup + */ + inline bool prepare_move_to_destination_dualx() { + if (active_extruder_parked) { + switch (dual_x_carriage_mode) { + case DXC_FULL_CONTROL_MODE: + break; + case DXC_AUTO_PARK_MODE: + if (current_position[E_AXIS] == destination[E_AXIS]) { + // This is a travel move (with no extrusion) + // Skip it, but keep track of the current position + // (so it can be used as the start of the next non-travel move) + if (delayed_move_time != 0xFFFFFFFFUL) { + set_current_to_destination(); + NOLESS(raised_parked_position[Z_AXIS], destination[Z_AXIS]); + delayed_move_time = millis(); + return false; + } + } + // unpark extruder: 1) raise, 2) move into starting XY position, 3) lower + for (uint8_t i = 0; i < 3; i++) + planner.buffer_line( + i == 0 ? raised_parked_position[X_AXIS] : current_position[X_AXIS], + i == 0 ? raised_parked_position[Y_AXIS] : current_position[Y_AXIS], + i == 2 ? current_position[Z_AXIS] : raised_parked_position[Z_AXIS], + current_position[E_AXIS], + i == 1 ? PLANNER_XY_FEEDRATE() : planner.max_feedrate_mm_s[Z_AXIS], + active_extruder + ); + delayed_move_time = 0; + active_extruder_parked = false; + break; + case DXC_DUPLICATION_MODE: + if (active_extruder == 0) { + // move duplicate extruder into correct duplication position. + planner.set_position_mm( + LOGICAL_X_POSITION(inactive_extruder_x_pos), + current_position[Y_AXIS], + current_position[Z_AXIS], + current_position[E_AXIS] + ); + planner.buffer_line( + current_position[X_AXIS] + duplicate_extruder_x_offset, + current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], + planner.max_feedrate_mm_s[X_AXIS], 1 + ); + SYNC_PLAN_POSITION_KINEMATIC(); + stepper.synchronize(); + extruder_duplication_enabled = true; + active_extruder_parked = false; + } + break; } - #if ENABLED(PREVENT_LENGTHY_EXTRUDE) - if (labs(de) > EXTRUDE_MAXLENGTH) { - curr_e = dest_e; // Behave as if the move really took place, but ignore E part - SERIAL_ECHO_START; - SERIAL_ECHOLNPGM(MSG_ERR_LONG_EXTRUDE_STOP); - } - #endif } + return true; } -#endif // PREVENT_DANGEROUS_EXTRUDE +#endif // DUAL_X_CARRIAGE /** * Prepare a single move and get ready for the next one * - * (This may call planner.buffer_line several times to put - * smaller moves into the planner for DELTA or SCARA.) + * This may result in several calls to planner.buffer_line to + * do smaller moves for DELTA, SCARA, mesh moves, etc. */ void prepare_move_to_destination() { clamp_to_software_endstops(destination); refresh_cmd_timeout(); - #if ENABLED(PREVENT_DANGEROUS_EXTRUDE) - prevent_dangerous_extrude(current_position[E_AXIS], destination[E_AXIS]); + #if ENABLED(PREVENT_COLD_EXTRUSION) + + if (!DEBUGGING(DRYRUN)) { + if (destination[E_AXIS] != current_position[E_AXIS]) { + if (thermalManager.tooColdToExtrude(active_extruder)) { + current_position[E_AXIS] = destination[E_AXIS]; // Behave as if the move really took place, but ignore E part + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM(MSG_ERR_COLD_EXTRUDE_STOP); + } + #if ENABLED(PREVENT_LENGTHY_EXTRUDE) + if (labs(destination[E_AXIS] - current_position[E_AXIS]) > EXTRUDE_MAXLENGTH) { + current_position[E_AXIS] = destination[E_AXIS]; // Behave as if the move really took place, but ignore E part + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM(MSG_ERR_LONG_EXTRUDE_STOP); + } + #endif + } + } + #endif - #if ENABLED(DELTA) || ENABLED(SCARA) + #if IS_KINEMATIC if (!prepare_kinematic_move_to(destination)) return; #else #if ENABLED(DUAL_X_CARRIAGE) @@ -8128,20 +9391,20 @@ void prepare_move_to_destination() { * options for G2/G3 arc generation. In future these options may be GCode tunable. */ void plan_arc( - float target[NUM_AXIS], // Destination position - float* offset, // Center of rotation relative to current_position - uint8_t clockwise // Clockwise? + float logical[NUM_AXIS], // Destination position + float* offset, // Center of rotation relative to current_position + uint8_t clockwise // Clockwise? ) { float radius = HYPOT(offset[X_AXIS], offset[Y_AXIS]), center_X = current_position[X_AXIS] + offset[X_AXIS], center_Y = current_position[Y_AXIS] + offset[Y_AXIS], - linear_travel = target[Z_AXIS] - current_position[Z_AXIS], - extruder_travel = target[E_AXIS] - current_position[E_AXIS], + linear_travel = logical[Z_AXIS] - current_position[Z_AXIS], + extruder_travel = logical[E_AXIS] - current_position[E_AXIS], r_X = -offset[X_AXIS], // Radius vector from center to current location r_Y = -offset[Y_AXIS], - rt_X = target[X_AXIS] - center_X, - rt_Y = target[Y_AXIS] - center_Y; + rt_X = logical[X_AXIS] - center_X, + rt_Y = logical[Y_AXIS] - center_Y; // CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required. float angular_travel = atan2(r_X * rt_Y - r_Y * rt_X, r_X * rt_X + r_Y * rt_Y); @@ -8149,23 +9412,20 @@ void prepare_move_to_destination() { if (clockwise) angular_travel -= RADIANS(360); // Make a circle if the angular rotation is 0 - if (angular_travel == 0 && current_position[X_AXIS] == target[X_AXIS] && current_position[Y_AXIS] == target[Y_AXIS]) + if (angular_travel == 0 && current_position[X_AXIS] == logical[X_AXIS] && current_position[Y_AXIS] == logical[Y_AXIS]) angular_travel += RADIANS(360); float mm_of_travel = HYPOT(angular_travel * radius, fabs(linear_travel)); if (mm_of_travel < 0.001) return; + uint16_t segments = floor(mm_of_travel / (MM_PER_ARC_SEGMENT)); if (segments == 0) segments = 1; - float theta_per_segment = angular_travel / segments; - float linear_per_segment = linear_travel / segments; - float extruder_per_segment = extruder_travel / segments; - /** * Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector, * and phi is the angle of rotation. Based on the solution approach by Jens Geisler. * r_T = [cos(phi) -sin(phi); - * sin(phi) cos(phi] * r ; + * sin(phi) cos(phi)] * r ; * * For arc generation, the center of the circle is the axis of rotation and the radius vector is * defined from the circle center to the initial position. Each line segment is formed by successive @@ -8188,13 +9448,12 @@ void prepare_move_to_destination() { * This is important when there are successive arc motions. */ // Vector rotation matrix values - float cos_T = 1 - 0.5 * sq(theta_per_segment); // Small angle approximation - float sin_T = theta_per_segment; - - float arc_target[NUM_AXIS]; - float sin_Ti, cos_Ti, r_new_Y; - uint16_t i; - int8_t count = 0; + float arc_target[XYZE], + theta_per_segment = angular_travel / segments, + linear_per_segment = linear_travel / segments, + extruder_per_segment = extruder_travel / segments, + sin_T = theta_per_segment, + cos_T = 1 - 0.5 * sq(theta_per_segment); // Small angle approximation // Initialize the linear axis arc_target[Z_AXIS] = current_position[Z_AXIS]; @@ -8202,22 +9461,22 @@ void prepare_move_to_destination() { // Initialize the extruder axis arc_target[E_AXIS] = current_position[E_AXIS]; - float fr_mm_s = MMM_TO_MMS_SCALED(feedrate_mm_m); + float fr_mm_s = MMS_SCALED(feedrate_mm_s); millis_t next_idle_ms = millis() + 200UL; - for (i = 1; i < segments; i++) { // Iterate (segments-1) times + int8_t count = 0; + for (uint16_t i = 1; i < segments; i++) { // Iterate (segments-1) times thermalManager.manage_heater(); - millis_t now = millis(); - if (ELAPSED(now, next_idle_ms)) { - next_idle_ms = now + 200UL; + if (ELAPSED(millis(), next_idle_ms)) { + next_idle_ms = millis() + 200UL; idle(); } if (++count < N_ARC_CORRECTION) { // Apply vector rotation matrix to previous r_X / 1 - r_new_Y = r_X * sin_T + r_Y * cos_T; + float r_new_Y = r_X * sin_T + r_Y * cos_T; r_X = r_X * cos_T - r_Y * sin_T; r_Y = r_new_Y; } @@ -8226,8 +9485,8 @@ void prepare_move_to_destination() { // Compute exact location by applying transformation matrix from initial radius vector(=-offset). // To reduce stuttering, the sin and cos could be computed at different times. // For now, compute both at the same time. - cos_Ti = cos(i * theta_per_segment); - sin_Ti = sin(i * theta_per_segment); + float cos_Ti = cos(i * theta_per_segment), + sin_Ti = sin(i * theta_per_segment); r_X = -offset[X_AXIS] * cos_Ti + offset[Y_AXIS] * sin_Ti; r_Y = -offset[X_AXIS] * sin_Ti - offset[Y_AXIS] * cos_Ti; count = 0; @@ -8241,27 +9500,11 @@ void prepare_move_to_destination() { clamp_to_software_endstops(arc_target); - #if ENABLED(DELTA) || ENABLED(SCARA) - inverse_kinematics(arc_target); - #if ENABLED(DELTA) && ENABLED(AUTO_BED_LEVELING_FEATURE) - adjust_delta(arc_target); - #endif - planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], arc_target[E_AXIS], fr_mm_s, active_extruder); - #else - planner.buffer_line(arc_target[X_AXIS], arc_target[Y_AXIS], arc_target[Z_AXIS], arc_target[E_AXIS], fr_mm_s, active_extruder); - #endif + planner.buffer_line_kinematic(arc_target, fr_mm_s, active_extruder); } // Ensure last segment arrives at target location. - #if ENABLED(DELTA) || ENABLED(SCARA) - inverse_kinematics(target); - #if ENABLED(DELTA) && ENABLED(AUTO_BED_LEVELING_FEATURE) - adjust_delta(target); - #endif - planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], target[E_AXIS], fr_mm_s, active_extruder); - #else - planner.buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], fr_mm_s, active_extruder); - #endif + planner.buffer_line_kinematic(logical, fr_mm_s, active_extruder); // As far as the parser is concerned, the position is now == target. In reality the // motion control system might still be processing the action and the real tool position @@ -8273,9 +9516,9 @@ void prepare_move_to_destination() { #if ENABLED(BEZIER_CURVE_SUPPORT) void plan_cubic_move(const float offset[4]) { - cubic_b_spline(current_position, destination, offset, MMM_TO_MMS_SCALED(feedrate_mm_m), active_extruder); + cubic_b_spline(current_position, destination, offset, MMS_SCALED(feedrate_mm_s), active_extruder); - // As far as the parser is concerned, the position is now == target. In reality the + // As far as the parser is concerned, the position is now == destination. In reality the // motion control system might still be processing the action and the real tool position // in any intermediate location. set_current_to_destination(); @@ -8320,85 +9563,86 @@ void prepare_move_to_destination() { #endif // HAS_CONTROLLERFAN -#if ENABLED(SCARA) +#if ENABLED(MORGAN_SCARA) - void forward_kinematics_SCARA(float f_scara[3]) { - // Perform forward kinematics, and place results in delta[3] - // The maths and first version has been done by QHARLEY . Integrated into masterbranch 06/2014 and slightly restructured by Joachim Cerny in June 2014 + /** + * Morgan SCARA Forward Kinematics. Results in cartes[]. + * Maths and first version by QHARLEY. + * Integrated into Marlin and slightly restructured by Joachim Cerny. + */ + void forward_kinematics_SCARA(const float &a, const float &b) { - float x_sin, x_cos, y_sin, y_cos; + float a_sin = sin(RADIANS(a)) * L1, + a_cos = cos(RADIANS(a)) * L1, + b_sin = sin(RADIANS(b)) * L2, + b_cos = cos(RADIANS(b)) * L2; - //SERIAL_ECHOPGM("f_delta x="); SERIAL_ECHO(f_scara[X_AXIS]); - //SERIAL_ECHOPGM(" y="); SERIAL_ECHO(f_scara[Y_AXIS]); + cartes[X_AXIS] = a_cos + b_cos + SCARA_OFFSET_X; //theta + cartes[Y_AXIS] = a_sin + b_sin + SCARA_OFFSET_Y; //theta+phi - x_sin = sin(f_scara[X_AXIS] / SCARA_RAD2DEG) * Linkage_1; - x_cos = cos(f_scara[X_AXIS] / SCARA_RAD2DEG) * Linkage_1; - y_sin = sin(f_scara[Y_AXIS] / SCARA_RAD2DEG) * Linkage_2; - y_cos = cos(f_scara[Y_AXIS] / SCARA_RAD2DEG) * Linkage_2; - - //SERIAL_ECHOPGM(" x_sin="); SERIAL_ECHO(x_sin); - //SERIAL_ECHOPGM(" x_cos="); SERIAL_ECHO(x_cos); - //SERIAL_ECHOPGM(" y_sin="); SERIAL_ECHO(y_sin); - //SERIAL_ECHOPGM(" y_cos="); SERIAL_ECHOLN(y_cos); - - delta[X_AXIS] = x_cos + y_cos + SCARA_offset_x; //theta - delta[Y_AXIS] = x_sin + y_sin + SCARA_offset_y; //theta+phi - - //SERIAL_ECHOPGM(" delta[X_AXIS]="); SERIAL_ECHO(delta[X_AXIS]); - //SERIAL_ECHOPGM(" delta[Y_AXIS]="); SERIAL_ECHOLN(delta[Y_AXIS]); + /* + SERIAL_ECHOPAIR("SCARA FK Angle a=", a); + SERIAL_ECHOPAIR(" b=", b); + SERIAL_ECHOPAIR(" a_sin=", a_sin); + SERIAL_ECHOPAIR(" a_cos=", a_cos); + SERIAL_ECHOPAIR(" b_sin=", b_sin); + SERIAL_ECHOLNPAIR(" b_cos=", b_cos); + SERIAL_ECHOPAIR(" cartes[X_AXIS]=", cartes[X_AXIS]); + SERIAL_ECHOLNPAIR(" cartes[Y_AXIS]=", cartes[Y_AXIS]); + //*/ } - void inverse_kinematics(const float cartesian[3]) { - // Inverse kinematics. - // Perform SCARA IK and place results in delta[3]. - // The maths and first version were done by QHARLEY. - // Integrated, tweaked by Joachim Cerny in June 2014. + /** + * Morgan SCARA Inverse Kinematics. Results in delta[]. + * + * See http://forums.reprap.org/read.php?185,283327 + * + * Maths and first version by QHARLEY. + * Integrated into Marlin and slightly restructured by Joachim Cerny. + */ + void inverse_kinematics(const float logical[XYZ]) { - float SCARA_pos[2]; - static float SCARA_C2, SCARA_S2, SCARA_K1, SCARA_K2, SCARA_theta, SCARA_psi; + static float C2, S2, SK1, SK2, THETA, PSI; - SCARA_pos[X_AXIS] = RAW_X_POSITION(cartesian[X_AXIS]) * axis_scaling[X_AXIS] - SCARA_offset_x; //Translate SCARA to standard X Y - SCARA_pos[Y_AXIS] = RAW_Y_POSITION(cartesian[Y_AXIS]) * axis_scaling[Y_AXIS] - SCARA_offset_y; // With scaling factor. + float sx = RAW_X_POSITION(logical[X_AXIS]) - SCARA_OFFSET_X, // Translate SCARA to standard X Y + sy = RAW_Y_POSITION(logical[Y_AXIS]) - SCARA_OFFSET_Y; // With scaling factor. - #if (Linkage_1 == Linkage_2) - SCARA_C2 = ((sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS])) / (2 * (float)L1_2)) - 1; - #else - SCARA_C2 = (sq(SCARA_pos[X_AXIS]) + sq(SCARA_pos[Y_AXIS]) - (float)L1_2 - (float)L2_2) / 45000; - #endif + if (L1 == L2) + C2 = HYPOT2(sx, sy) / L1_2_2 - 1; + else + C2 = (HYPOT2(sx, sy) - (L1_2 + L2_2)) / (2.0 * L1 * L2); - SCARA_S2 = sqrt(1 - sq(SCARA_C2)); + S2 = sqrt(sq(C2) - 1); - SCARA_K1 = Linkage_1 + Linkage_2 * SCARA_C2; - SCARA_K2 = Linkage_2 * SCARA_S2; + // Unrotated Arm1 plus rotated Arm2 gives the distance from Center to End + SK1 = L1 + L2 * C2; - SCARA_theta = (atan2(SCARA_pos[X_AXIS], SCARA_pos[Y_AXIS]) - atan2(SCARA_K1, SCARA_K2)) * -1; - SCARA_psi = atan2(SCARA_S2, SCARA_C2); + // Rotated Arm2 gives the distance from Arm1 to Arm2 + SK2 = L2 * S2; - delta[X_AXIS] = SCARA_theta * SCARA_RAD2DEG; // Multiply by 180/Pi - theta is support arm angle - delta[Y_AXIS] = (SCARA_theta + SCARA_psi) * SCARA_RAD2DEG; // - equal to sub arm angle (inverted motor) - delta[Z_AXIS] = RAW_Z_POSITION(cartesian[Z_AXIS]); + // Angle of Arm1 is the difference between Center-to-End angle and the Center-to-Elbow + THETA = atan2(SK1, SK2) - atan2(sx, sy); - /** - SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]); - SERIAL_ECHOPGM(" y="); SERIAL_ECHO(cartesian[Y_AXIS]); - SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(cartesian[Z_AXIS]); + // Angle of Arm2 + PSI = atan2(S2, C2); - SERIAL_ECHOPGM("scara x="); SERIAL_ECHO(SCARA_pos[X_AXIS]); - SERIAL_ECHOPGM(" y="); SERIAL_ECHOLN(SCARA_pos[Y_AXIS]); + delta[A_AXIS] = DEGREES(THETA); // theta is support arm angle + delta[B_AXIS] = DEGREES(THETA + PSI); // equal to sub arm angle (inverted motor) + delta[C_AXIS] = logical[Z_AXIS]; - SERIAL_ECHOPGM("delta x="); SERIAL_ECHO(delta[X_AXIS]); - SERIAL_ECHOPGM(" y="); SERIAL_ECHO(delta[Y_AXIS]); - SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(delta[Z_AXIS]); - - SERIAL_ECHOPGM("C2="); SERIAL_ECHO(SCARA_C2); - SERIAL_ECHOPGM(" S2="); SERIAL_ECHO(SCARA_S2); - SERIAL_ECHOPGM(" Theta="); SERIAL_ECHO(SCARA_theta); - SERIAL_ECHOPGM(" Psi="); SERIAL_ECHOLN(SCARA_psi); - SERIAL_EOL; - */ + /* + DEBUG_POS("SCARA IK", logical); + DEBUG_POS("SCARA IK", delta); + SERIAL_ECHOPAIR(" SCARA (x,y) ", sx); + SERIAL_ECHOPAIR(",", sy); + SERIAL_ECHOPAIR(" C2=", C2); + SERIAL_ECHOPAIR(" S2=", S2); + SERIAL_ECHOPAIR(" Theta=", THETA); + SERIAL_ECHOLNPAIR(" Phi=", PHI); + //*/ } -#endif // SCARA +#endif // MORGAN_SCARA #if ENABLED(TEMP_STAT_LEDS) @@ -8406,26 +9650,116 @@ void prepare_move_to_destination() { static millis_t next_status_led_update_ms = 0; void handle_status_leds(void) { - float max_temp = 0.0; if (ELAPSED(millis(), next_status_led_update_ms)) { next_status_led_update_ms += 500; // Update every 0.5s - HOTEND_LOOP() { - max_temp = max(max(max_temp, thermalManager.degHotend(e)), thermalManager.degTargetHotend(e)); - } + float max_temp = 0.0; #if HAS_TEMP_BED - max_temp = max(max(max_temp, thermalManager.degTargetBed()), thermalManager.degBed()); + max_temp = MAX3(max_temp, thermalManager.degTargetBed(), thermalManager.degBed()); #endif + HOTEND_LOOP() { + max_temp = MAX3(max_temp, thermalManager.degHotend(e), thermalManager.degTargetHotend(e)); + } bool new_led = (max_temp > 55.0) ? true : (max_temp < 54.0) ? false : red_led; if (new_led != red_led) { red_led = new_led; - digitalWrite(STAT_LED_RED, new_led ? HIGH : LOW); - digitalWrite(STAT_LED_BLUE, new_led ? LOW : HIGH); + #if PIN_EXISTS(STAT_LED_RED) + WRITE(STAT_LED_RED_PIN, new_led ? HIGH : LOW); + #if PIN_EXISTS(STAT_LED_BLUE) + WRITE(STAT_LED_BLUE_PIN, new_led ? LOW : HIGH); + #endif + #else + WRITE(STAT_LED_BLUE_PIN, new_led ? HIGH : LOW); + #endif } } } #endif +#if ENABLED(FILAMENT_RUNOUT_SENSOR) + + void handle_filament_runout() { + if (!filament_ran_out) { + filament_ran_out = true; + enqueue_and_echo_commands_P(PSTR(FILAMENT_RUNOUT_SCRIPT)); + stepper.synchronize(); + } + } + +#endif // FILAMENT_RUNOUT_SENSOR + +#if ENABLED(FAST_PWM_FAN) + + void setPwmFrequency(uint8_t pin, int val) { + val &= 0x07; + switch (digitalPinToTimer(pin)) { + #if defined(TCCR0A) + case TIMER0A: + case TIMER0B: + // TCCR0B &= ~(_BV(CS00) | _BV(CS01) | _BV(CS02)); + // TCCR0B |= val; + break; + #endif + #if defined(TCCR1A) + case TIMER1A: + case TIMER1B: + // TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12)); + // TCCR1B |= val; + break; + #endif + #if defined(TCCR2) + case TIMER2: + case TIMER2: + TCCR2 &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12)); + TCCR2 |= val; + break; + #endif + #if defined(TCCR2A) + case TIMER2A: + case TIMER2B: + TCCR2B &= ~(_BV(CS20) | _BV(CS21) | _BV(CS22)); + TCCR2B |= val; + break; + #endif + #if defined(TCCR3A) + case TIMER3A: + case TIMER3B: + case TIMER3C: + TCCR3B &= ~(_BV(CS30) | _BV(CS31) | _BV(CS32)); + TCCR3B |= val; + break; + #endif + #if defined(TCCR4A) + case TIMER4A: + case TIMER4B: + case TIMER4C: + TCCR4B &= ~(_BV(CS40) | _BV(CS41) | _BV(CS42)); + TCCR4B |= val; + break; + #endif + #if defined(TCCR5A) + case TIMER5A: + case TIMER5B: + case TIMER5C: + TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52)); + TCCR5B |= val; + break; + #endif + } + } + +#endif // FAST_PWM_FAN + +float calculate_volumetric_multiplier(float diameter) { + if (!volumetric_enabled || diameter == 0) return 1.0; + return 1.0 / (M_PI * diameter * 0.5 * diameter * 0.5); +} + +void calculate_volumetric_multipliers() { + for (uint8_t i = 0; i < COUNT(filament_size); i++) + volumetric_multiplier[i] = calculate_volumetric_multiplier(filament_size[i]); +} + void enable_all_steppers() { enable_x(); enable_y(); @@ -8446,33 +9780,6 @@ void disable_all_steppers() { disable_e3(); } -/** - * Standard idle routine keeps the machine alive - */ -void idle( - #if ENABLED(FILAMENT_CHANGE_FEATURE) - bool no_stepper_sleep/*=false*/ - #endif -) { - lcd_update(); - host_keepalive(); - manage_inactivity( - #if ENABLED(FILAMENT_CHANGE_FEATURE) - no_stepper_sleep - #endif - ); - - thermalManager.manage_heater(); - - #if ENABLED(PRINTCOUNTER) - print_job_timer.tick(); - #endif - - #if HAS_BUZZER && PIN_EXISTS(BEEPER) - buzzer.tick(); - #endif -} - /** * Manage several activities: * - Check for Filament Runout @@ -8488,7 +9795,7 @@ void idle( void manage_inactivity(bool ignore_stepper_queue/*=false*/) { #if ENABLED(FILAMENT_RUNOUT_SENSOR) - if ((IS_SD_PRINTING || print_job_timer.isRunning()) && !(READ(FIL_RUNOUT_PIN) ^ FIL_RUNOUT_INVERTING)) + if ((IS_SD_PRINTING || print_job_timer.isRunning()) && (READ(FIL_RUNOUT_PIN) == FIL_RUNOUT_INVERTING)) handle_filament_runout(); #endif @@ -8566,11 +9873,11 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { #if ENABLED(EXTRUDER_RUNOUT_PREVENT) if (ELAPSED(ms, previous_cmd_ms + (EXTRUDER_RUNOUT_SECONDS) * 1000UL) && thermalManager.degHotend(active_extruder) > EXTRUDER_RUNOUT_MINTEMP) { + bool oldstatus; #if ENABLED(SWITCHING_EXTRUDER) - bool oldstatus = E0_ENABLE_READ; + oldstatus = E0_ENABLE_READ; enable_e0(); #else // !SWITCHING_EXTRUDER - bool oldstatus; switch (active_extruder) { case 0: oldstatus = E0_ENABLE_READ; @@ -8597,15 +9904,25 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { } #endif // !SWITCHING_EXTRUDER - float oldepos = current_position[E_AXIS], oldedes = destination[E_AXIS]; - planner.buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], - destination[E_AXIS] + (EXTRUDER_RUNOUT_EXTRUDE) * (EXTRUDER_RUNOUT_ESTEPS) / planner.axis_steps_per_mm[E_AXIS], - MMM_TO_MMS(EXTRUDER_RUNOUT_SPEED) * (EXTRUDER_RUNOUT_ESTEPS) / planner.axis_steps_per_mm[E_AXIS], active_extruder); - current_position[E_AXIS] = oldepos; - destination[E_AXIS] = oldedes; - planner.set_e_position_mm(oldepos); previous_cmd_ms = ms; // refresh_cmd_timeout() + + #if IS_KINEMATIC + inverse_kinematics(current_position); + ADJUST_DELTA(current_position); + planner.buffer_line( + delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], + current_position[E_AXIS] + EXTRUDER_RUNOUT_EXTRUDE, + MMM_TO_MMS(EXTRUDER_RUNOUT_SPEED), active_extruder + ); + #else + planner.buffer_line( + current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], + current_position[E_AXIS] + EXTRUDER_RUNOUT_EXTRUDE, + MMM_TO_MMS(EXTRUDER_RUNOUT_SPEED), active_extruder + ); + #endif stepper.synchronize(); + planner.set_e_position_mm(current_position[E_AXIS]); #if ENABLED(SWITCHING_EXTRUDER) E0_ENABLE_WRITE(oldstatus); #else @@ -8650,6 +9967,43 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { planner.check_axes_activity(); } +/** + * Standard idle routine keeps the machine alive + */ +void idle( + #if ENABLED(FILAMENT_CHANGE_FEATURE) + bool no_stepper_sleep/*=false*/ + #endif +) { + lcd_update(); + + host_keepalive(); + + #if ENABLED(AUTO_REPORT_TEMPERATURES) && (HAS_TEMP_HOTEND || HAS_TEMP_BED) + auto_report_temperatures(); + #endif + + manage_inactivity( + #if ENABLED(FILAMENT_CHANGE_FEATURE) + no_stepper_sleep + #endif + ); + + thermalManager.manage_heater(); + + #if ENABLED(PRINTCOUNTER) + print_job_timer.tick(); + #endif + + #if HAS_BUZZER && DISABLED(LCD_USE_I2C_BUZZER) + buzzer.tick(); + #endif +} + +/** + * Kill all activity and lock the machine. + * After this the machine will need to be reset. + */ void kill(const char* lcd_msg) { SERIAL_ERROR_START; SERIAL_ERRORLNPGM(MSG_ERR_KILLED); @@ -8660,14 +10014,14 @@ void kill(const char* lcd_msg) { UNUSED(lcd_msg); #endif - for (int i = 5; i--;) delay(100); // Wait a short time + delay(500); // Wait a short time cli(); // Stop interrupts thermalManager.disable_all_heaters(); disable_all_steppers(); #if HAS_POWER_SWITCH - pinMode(PS_ON_PIN, INPUT); + SET_INPUT(PS_ON_PIN); #endif suicide(); @@ -8678,79 +10032,10 @@ void kill(const char* lcd_msg) { } // Wait for reset } -#if ENABLED(FILAMENT_RUNOUT_SENSOR) - - void handle_filament_runout() { - if (!filament_ran_out) { - filament_ran_out = true; - enqueue_and_echo_commands_P(PSTR(FILAMENT_RUNOUT_SCRIPT)); - stepper.synchronize(); - } - } - -#endif // FILAMENT_RUNOUT_SENSOR - -#if ENABLED(FAST_PWM_FAN) - - void setPwmFrequency(uint8_t pin, int val) { - val &= 0x07; - switch (digitalPinToTimer(pin)) { - #if defined(TCCR0A) - case TIMER0A: - case TIMER0B: - // TCCR0B &= ~(_BV(CS00) | _BV(CS01) | _BV(CS02)); - // TCCR0B |= val; - break; - #endif - #if defined(TCCR1A) - case TIMER1A: - case TIMER1B: - // TCCR1B &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12)); - // TCCR1B |= val; - break; - #endif - #if defined(TCCR2) - case TIMER2: - case TIMER2: - TCCR2 &= ~(_BV(CS10) | _BV(CS11) | _BV(CS12)); - TCCR2 |= val; - break; - #endif - #if defined(TCCR2A) - case TIMER2A: - case TIMER2B: - TCCR2B &= ~(_BV(CS20) | _BV(CS21) | _BV(CS22)); - TCCR2B |= val; - break; - #endif - #if defined(TCCR3A) - case TIMER3A: - case TIMER3B: - case TIMER3C: - TCCR3B &= ~(_BV(CS30) | _BV(CS31) | _BV(CS32)); - TCCR3B |= val; - break; - #endif - #if defined(TCCR4A) - case TIMER4A: - case TIMER4B: - case TIMER4C: - TCCR4B &= ~(_BV(CS40) | _BV(CS41) | _BV(CS42)); - TCCR4B |= val; - break; - #endif - #if defined(TCCR5A) - case TIMER5A: - case TIMER5B: - case TIMER5C: - TCCR5B &= ~(_BV(CS50) | _BV(CS51) | _BV(CS52)); - TCCR5B |= val; - break; - #endif - } - } -#endif // FAST_PWM_FAN - +/** + * Turn off heaters and stop the print in progress + * After a stop the machine may be resumed with M999 + */ void stop() { thermalManager.disable_all_heaters(); if (IsRunning()) { @@ -8762,13 +10047,228 @@ void stop() { } } -float calculate_volumetric_multiplier(float diameter) { - if (!volumetric_enabled || diameter == 0) return 1.0; - float d2 = diameter * 0.5; - return 1.0 / (M_PI * d2 * d2); +/** + * Marlin entry-point: Set up before the program loop + * - Set up the kill pin, filament runout, power hold + * - Start the serial port + * - Print startup messages and diagnostics + * - Get EEPROM or default settings + * - Initialize managers for: + * • temperature + * • planner + * • watchdog + * • stepper + * • photo pin + * • servos + * • LCD controller + * • Digipot I2C + * • Z probe sled + * • status LEDs + */ +void setup() { + + #ifdef DISABLE_JTAG + // Disable JTAG on AT90USB chips to free up pins for IO + MCUCR = 0x80; + MCUCR = 0x80; + #endif + + #if ENABLED(FILAMENT_RUNOUT_SENSOR) + setup_filrunoutpin(); + #endif + + setup_killpin(); + + setup_powerhold(); + + #if HAS_STEPPER_RESET + disableStepperDrivers(); + #endif + + MYSERIAL.begin(BAUDRATE); + SERIAL_PROTOCOLLNPGM("start"); + SERIAL_ECHO_START; + + // Check startup - does nothing if bootloader sets MCUSR to 0 + byte mcu = MCUSR; + if (mcu & 1) SERIAL_ECHOLNPGM(MSG_POWERUP); + if (mcu & 2) SERIAL_ECHOLNPGM(MSG_EXTERNAL_RESET); + if (mcu & 4) SERIAL_ECHOLNPGM(MSG_BROWNOUT_RESET); + if (mcu & 8) SERIAL_ECHOLNPGM(MSG_WATCHDOG_RESET); + if (mcu & 32) SERIAL_ECHOLNPGM(MSG_SOFTWARE_RESET); + MCUSR = 0; + + SERIAL_ECHOPGM(MSG_MARLIN); + SERIAL_CHAR(' '); + SERIAL_ECHOLNPGM(SHORT_BUILD_VERSION); + SERIAL_EOL; + + #if defined(STRING_DISTRIBUTION_DATE) && defined(STRING_CONFIG_H_AUTHOR) + SERIAL_ECHO_START; + SERIAL_ECHOPGM(MSG_CONFIGURATION_VER); + SERIAL_ECHOPGM(STRING_DISTRIBUTION_DATE); + SERIAL_ECHOLNPGM(MSG_AUTHOR STRING_CONFIG_H_AUTHOR); + SERIAL_ECHOLNPGM("Compiled: " __DATE__); + #endif + + SERIAL_ECHO_START; + SERIAL_ECHOPAIR(MSG_FREE_MEMORY, freeMemory()); + SERIAL_ECHOLNPAIR(MSG_PLANNER_BUFFER_BYTES, (int)sizeof(block_t)*BLOCK_BUFFER_SIZE); + + // Send "ok" after commands by default + for (int8_t i = 0; i < BUFSIZE; i++) send_ok[i] = true; + + // Load data from EEPROM if available (or use defaults) + // This also updates variables in the planner, elsewhere + Config_RetrieveSettings(); + + // Initialize current position based on home_offset + memcpy(current_position, home_offset, sizeof(home_offset)); + + // Vital to init stepper/planner equivalent for current_position + SYNC_PLAN_POSITION_KINEMATIC(); + + thermalManager.init(); // Initialize temperature loop + + #if ENABLED(USE_WATCHDOG) + watchdog_init(); + #endif + + stepper.init(); // Initialize stepper, this enables interrupts! + servo_init(); + + #if HAS_PHOTOGRAPH + OUT_WRITE(PHOTOGRAPH_PIN, LOW); + #endif + + #if HAS_CASE_LIGHT + update_case_light(); + #endif + + #if HAS_BED_PROBE + endstops.enable_z_probe(false); + #endif + + #if HAS_CONTROLLERFAN + SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan + #endif + + #if HAS_STEPPER_RESET + enableStepperDrivers(); + #endif + + #if ENABLED(DIGIPOT_I2C) + digipot_i2c_init(); + #endif + + #if ENABLED(DAC_STEPPER_CURRENT) + dac_init(); + #endif + + #if ENABLED(Z_PROBE_SLED) && PIN_EXISTS(SLED) + OUT_WRITE(SLED_PIN, LOW); // turn it off + #endif // Z_PROBE_SLED + + setup_homepin(); + + #if PIN_EXISTS(STAT_LED_RED) + OUT_WRITE(STAT_LED_RED_PIN, LOW); // turn it off + #endif + + #if PIN_EXISTS(STAT_LED_BLUE) + OUT_WRITE(STAT_LED_BLUE_PIN, LOW); // turn it off + #endif + + #if ENABLED(RGB_LED) + pinMode(RGB_LED_R_PIN, OUTPUT); + pinMode(RGB_LED_G_PIN, OUTPUT); + pinMode(RGB_LED_B_PIN, OUTPUT); + #endif + + lcd_init(); + #if ENABLED(SHOW_BOOTSCREEN) + #if ENABLED(DOGLCD) + safe_delay(BOOTSCREEN_TIMEOUT); + #elif ENABLED(ULTRA_LCD) + bootscreen(); + #if DISABLED(SDSUPPORT) + lcd_init(); + #endif + #endif + #endif + + #if ENABLED(MIXING_EXTRUDER) && MIXING_VIRTUAL_TOOLS > 1 + // Initialize mixing to 100% color 1 + for (uint8_t i = 0; i < MIXING_STEPPERS; i++) + mixing_factor[i] = (i == 0) ? 1.0 : 0.0; + for (uint8_t t = 0; t < MIXING_VIRTUAL_TOOLS; t++) + for (uint8_t i = 0; i < MIXING_STEPPERS; i++) + mixing_virtual_tool_mix[t][i] = mixing_factor[i]; + #endif + + #if ENABLED(EXPERIMENTAL_I2CBUS) && I2C_SLAVE_ADDRESS > 0 + i2c.onReceive(i2c_on_receive); + i2c.onRequest(i2c_on_request); + #endif + + #if ENABLED(ENDSTOP_INTERRUPTS_FEATURE) + setup_endstop_interrupts(); + #endif } -void calculate_volumetric_multipliers() { - for (uint8_t i = 0; i < COUNT(filament_size); i++) - volumetric_multiplier[i] = calculate_volumetric_multiplier(filament_size[i]); +/** + * The main Marlin program loop + * + * - Save or log commands to SD + * - Process available commands (if not saving) + * - Call heater manager + * - Call inactivity manager + * - Call endstop manager + * - Call LCD update + */ +void loop() { + if (commands_in_queue < BUFSIZE) get_available_commands(); + + #if ENABLED(SDSUPPORT) + card.checkautostart(false); + #endif + + if (commands_in_queue) { + + #if ENABLED(SDSUPPORT) + + if (card.saving) { + char* command = command_queue[cmd_queue_index_r]; + if (strstr_P(command, PSTR("M29"))) { + // M29 closes the file + card.closefile(); + SERIAL_PROTOCOLLNPGM(MSG_FILE_SAVED); + ok_to_send(); + } + else { + // Write the string from the read buffer to SD + card.write_command(command); + if (card.logging) + process_next_command(); // The card is saving because it's logging + else + ok_to_send(); + } + } + else + process_next_command(); + + #else + + process_next_command(); + + #endif // SDSUPPORT + + // The queue may be reset by a command handler or by code invoked by idle() within a handler + if (commands_in_queue) { + --commands_in_queue; + cmd_queue_index_r = (cmd_queue_index_r + 1) % BUFSIZE; + } + } + endstops.report_state(); + idle(); } diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index bec3d462b7..0431a820f0 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -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 diff --git a/Marlin/Sd2Card.cpp b/Marlin/Sd2Card.cpp index 190e4ad1ff..900c73b53d 100644 --- a/Marlin/Sd2Card.cpp +++ b/Marlin/Sd2Card.cpp @@ -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; diff --git a/Marlin/SdBaseFile.cpp b/Marlin/SdBaseFile.cpp index 95765f9c18..298cdd1147 100644 --- a/Marlin/SdBaseFile.cpp +++ b/Marlin/SdBaseFile.cpp @@ -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 diff --git a/Marlin/SdFatUtil.h b/Marlin/SdFatUtil.h index 9db81ac570..2e6435bbdc 100644 --- a/Marlin/SdFatUtil.h +++ b/Marlin/SdFatUtil.h @@ -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 diff --git a/Marlin/boards.h b/Marlin/boards.h index bf7be0edf6..e8ac50a4d6 100644 --- a/Marlin/boards.h +++ b/Marlin/boards.h @@ -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 diff --git a/Marlin/buzzer.h b/Marlin/buzzer.h index 199d64e419..9441875303 100644 --- a/Marlin/buzzer.h +++ b/Marlin/buzzer.h @@ -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); } /** diff --git a/Marlin/cardreader.cpp b/Marlin/cardreader.cpp index 65b40933ae..e79200c2cb 100644 --- a/Marlin/cardreader.cpp +++ b/Marlin/cardreader.cpp @@ -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 { diff --git a/Marlin/cardreader.h b/Marlin/cardreader.h index 8c22e581c8..b0ed92b89d 100644 --- a/Marlin/cardreader.h +++ b/Marlin/cardreader.h @@ -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(); } diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index db10bba150..a3ae225b22 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -36,93 +36,88 @@ * */ -#define EEPROM_VERSION "V24" +#define EEPROM_VERSION "V27" // Change EEPROM version if these are changed: #define EEPROM_OFFSET 100 -#define MAX_EXTRUDERS 4 /** - * V24 EEPROM Layout: + * V27 EEPROM Layout: * * 100 Version (char x4) * 104 EEPROM Checksum (uint16_t) * - * 106 M92 XYZE planner.axis_steps_per_mm (float x4) - * 122 M203 XYZE planner.max_feedrate_mm_s (float x4) - * 138 M201 XYZE planner.max_acceleration_mm_per_s2 (uint32_t x4) + * 106 M92 XYZE planner.axis_steps_per_mm (float x4 ... x7) + * 122 M203 XYZE planner.max_feedrate_mm_s (float x4 ... x7) + * 138 M201 XYZE planner.max_acceleration_mm_per_s2 (uint32_t x4 ... x7) * 154 M204 P planner.acceleration (float) * 158 M204 R planner.retract_acceleration (float) * 162 M204 T planner.travel_acceleration (float) * 166 M205 S planner.min_feedrate_mm_s (float) * 170 M205 T planner.min_travel_feedrate_mm_s (float) * 174 M205 B planner.min_segment_time (ulong) - * 178 M205 X planner.max_xy_jerk (float) - * 182 M205 Z planner.max_z_jerk (float) - * 186 M205 E planner.max_e_jerk (float) - * 190 M206 XYZ home_offset (float x3) + * 178 M205 X planner.max_jerk[X_AXIS] (float) + * 182 M205 Y planner.max_jerk[Y_AXIS] (float) + * 186 M205 Z planner.max_jerk[Z_AXIS] (float) + * 190 M205 E planner.max_jerk[E_AXIS] (float) + * 194 M206 XYZ home_offset (float x3) + * 206 M218 XYZ hotend_offset (float x3 per additional hotend) * * Mesh bed leveling: - * 202 M420 S status (uint8) - * 203 z_offset (float) - * 207 mesh_num_x (uint8 as set in firmware) - * 208 mesh_num_y (uint8 as set in firmware) - * 209 G29 S3 XYZ z_values[][] (float x9, by default, up to float x 81) + * 218 M420 S status (uint8) + * 219 z_offset (float) + * 223 mesh_num_x (uint8 as set in firmware) + * 224 mesh_num_y (uint8 as set in firmware) + * 225 G29 S3 XYZ z_values[][] (float x9, by default, up to float x 81) * * AUTO BED LEVELING - * 245 M851 zprobe_zoffset (float) + * 261 M851 zprobe_zoffset (float) * * DELTA: - * 249 M666 XYZ endstop_adj (float x3) - * 261 M665 R delta_radius (float) - * 265 M665 L delta_diagonal_rod (float) - * 269 M665 S delta_segments_per_second (float) - * 273 M665 A delta_diagonal_rod_trim_tower_1 (float) - * 277 M665 B delta_diagonal_rod_trim_tower_2 (float) - * 281 M665 C delta_diagonal_rod_trim_tower_3 (float) + * 265 M666 XYZ endstop_adj (float x3) + * 277 M665 R delta_radius (float) + * 281 M665 L delta_diagonal_rod (float) + * 285 M665 S delta_segments_per_second (float) + * 289 M665 A delta_diagonal_rod_trim_tower_1 (float) + * 293 M665 B delta_diagonal_rod_trim_tower_2 (float) + * 297 M665 C delta_diagonal_rod_trim_tower_3 (float) * * Z_DUAL_ENDSTOPS: - * 285 M666 Z z_endstop_adj (float) + * 301 M666 Z z_endstop_adj (float) * * ULTIPANEL: - * 289 M145 S0 H preheatHotendTemp1 (int) - * 291 M145 S0 B preheatBedTemp1 (int) - * 293 M145 S0 F preheatFanSpeed1 (int) - * 295 M145 S1 H preheatHotendTemp2 (int) - * 297 M145 S1 B preheatBedTemp2 (int) - * 299 M145 S1 F preheatFanSpeed2 (int) + * 305 M145 S0 H lcd_preheat_hotend_temp (int x2) + * 309 M145 S0 B lcd_preheat_bed_temp (int x2) + * 313 M145 S0 F lcd_preheat_fan_speed (int x2) * * PIDTEMP: - * 301 M301 E0 PIDC Kp[0], Ki[0], Kd[0], Kc[0] (float x4) - * 317 M301 E1 PIDC Kp[1], Ki[1], Kd[1], Kc[1] (float x4) - * 333 M301 E2 PIDC Kp[2], Ki[2], Kd[2], Kc[2] (float x4) - * 349 M301 E3 PIDC Kp[3], Ki[3], Kd[3], Kc[3] (float x4) - * 365 M301 L lpq_len (int) + * 317 M301 E0 PIDC Kp[0], Ki[0], Kd[0], Kc[0] (float x4) + * 333 M301 E1 PIDC Kp[1], Ki[1], Kd[1], Kc[1] (float x4) + * 349 M301 E2 PIDC Kp[2], Ki[2], Kd[2], Kc[2] (float x4) + * 365 M301 E3 PIDC Kp[3], Ki[3], Kd[3], Kc[3] (float x4) + * 381 M301 L lpq_len (int) * * PIDTEMPBED: - * 367 M304 PID thermalManager.bedKp, thermalManager.bedKi, thermalManager.bedKd (float x3) + * 383 M304 PID thermalManager.bedKp, thermalManager.bedKi, thermalManager.bedKd (float x3) * * DOGLCD: - * 379 M250 C lcd_contrast (int) - * - * SCARA: - * 381 M365 XYZ axis_scaling (float x3) + * 395 M250 C lcd_contrast (int) * * FWRETRACT: - * 393 M209 S autoretract_enabled (bool) - * 394 M207 S retract_length (float) - * 398 M207 W retract_length_swap (float) - * 402 M207 F retract_feedrate_mm_s (float) - * 406 M207 Z retract_zlift (float) - * 410 M208 S retract_recover_length (float) - * 414 M208 W retract_recover_length_swap (float) - * 418 M208 F retract_recover_feedrate_mm_s (float) + * 397 M209 S autoretract_enabled (bool) + * 398 M207 S retract_length (float) + * 402 M207 W retract_length_swap (float) + * 406 M207 F retract_feedrate_mm_s (float) + * 410 M207 Z retract_zlift (float) + * 414 M208 S retract_recover_length (float) + * 418 M208 W retract_recover_length_swap (float) + * 422 M208 F retract_recover_feedrate_mm_s (float) * * Volumetric Extrusion: - * 422 M200 D volumetric_enabled (bool) - * 423 M200 T D filament_size (float x4) (T0..3) + * 426 M200 D volumetric_enabled (bool) + * 427 M200 T D filament_size (float x4) (T0..3) * - * 439 This Slot is Available! + * 443 This Slot is Available! * */ #include "Marlin.h" @@ -186,6 +181,9 @@ void Config_Postprocess() { #endif calculate_volumetric_multipliers(); + + // Software endstops depend on home_offset + LOOP_XYZ(i) update_software_endstops((AxisEnum)i); } #if ENABLED(EEPROM_SETTINGS) @@ -196,395 +194,387 @@ void Config_Postprocess() { #define EEPROM_WRITE(VAR) _EEPROM_writeData(eeprom_index, (uint8_t*)&VAR, sizeof(VAR)) #define EEPROM_READ(VAR) _EEPROM_readData(eeprom_index, (uint8_t*)&VAR, sizeof(VAR)) -/** - * M500 - Store Configuration - */ -void Config_StoreSettings() { - float dummy = 0.0f; - char ver[4] = "000"; + /** + * M500 - Store Configuration + */ + void Config_StoreSettings() { + float dummy = 0.0f; + char ver[4] = "000"; - EEPROM_START(); + EEPROM_START(); - EEPROM_WRITE(ver); // invalidate data first - EEPROM_SKIP(eeprom_checksum); // Skip the checksum slot + EEPROM_WRITE(ver); // invalidate data first + EEPROM_SKIP(eeprom_checksum); // Skip the checksum slot - eeprom_checksum = 0; // clear before first "real data" + eeprom_checksum = 0; // clear before first "real data" - EEPROM_WRITE(planner.axis_steps_per_mm); - EEPROM_WRITE(planner.max_feedrate_mm_s); - EEPROM_WRITE(planner.max_acceleration_mm_per_s2); - EEPROM_WRITE(planner.acceleration); - EEPROM_WRITE(planner.retract_acceleration); - EEPROM_WRITE(planner.travel_acceleration); - EEPROM_WRITE(planner.min_feedrate_mm_s); - EEPROM_WRITE(planner.min_travel_feedrate_mm_s); - EEPROM_WRITE(planner.min_segment_time); - EEPROM_WRITE(planner.max_xy_jerk); - EEPROM_WRITE(planner.max_z_jerk); - EEPROM_WRITE(planner.max_e_jerk); - EEPROM_WRITE(home_offset); + EEPROM_WRITE(planner.axis_steps_per_mm); + EEPROM_WRITE(planner.max_feedrate_mm_s); + EEPROM_WRITE(planner.max_acceleration_mm_per_s2); + EEPROM_WRITE(planner.acceleration); + EEPROM_WRITE(planner.retract_acceleration); + EEPROM_WRITE(planner.travel_acceleration); + EEPROM_WRITE(planner.min_feedrate_mm_s); + EEPROM_WRITE(planner.min_travel_feedrate_mm_s); + EEPROM_WRITE(planner.min_segment_time); + EEPROM_WRITE(planner.max_jerk); + EEPROM_WRITE(home_offset); - #if ENABLED(MESH_BED_LEVELING) - // Compile time test that sizeof(mbl.z_values) is as expected - typedef char c_assert[(sizeof(mbl.z_values) == (MESH_NUM_X_POINTS) * (MESH_NUM_Y_POINTS) * sizeof(dummy)) ? 1 : -1]; - uint8_t mesh_num_x = MESH_NUM_X_POINTS, - mesh_num_y = MESH_NUM_Y_POINTS, - dummy_uint8 = mbl.status & _BV(MBL_STATUS_HAS_MESH_BIT); - EEPROM_WRITE(dummy_uint8); - EEPROM_WRITE(mbl.z_offset); - EEPROM_WRITE(mesh_num_x); - EEPROM_WRITE(mesh_num_y); - EEPROM_WRITE(mbl.z_values); - #else - // For disabled MBL write a default mesh - uint8_t mesh_num_x = 3, - mesh_num_y = 3, - dummy_uint8 = 0; - dummy = 0.0f; - EEPROM_WRITE(dummy_uint8); - EEPROM_WRITE(dummy); - EEPROM_WRITE(mesh_num_x); - EEPROM_WRITE(mesh_num_y); - for (uint8_t q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_WRITE(dummy); - #endif // MESH_BED_LEVELING - - #if !HAS_BED_PROBE - float zprobe_zoffset = 0; - #endif - EEPROM_WRITE(zprobe_zoffset); - - // 9 floats for DELTA / Z_DUAL_ENDSTOPS - #if ENABLED(DELTA) - EEPROM_WRITE(endstop_adj); // 3 floats - EEPROM_WRITE(delta_radius); // 1 float - EEPROM_WRITE(delta_diagonal_rod); // 1 float - EEPROM_WRITE(delta_segments_per_second); // 1 float - EEPROM_WRITE(delta_diagonal_rod_trim_tower_1); // 1 float - EEPROM_WRITE(delta_diagonal_rod_trim_tower_2); // 1 float - EEPROM_WRITE(delta_diagonal_rod_trim_tower_3); // 1 float - #elif ENABLED(Z_DUAL_ENDSTOPS) - EEPROM_WRITE(z_endstop_adj); // 1 float - dummy = 0.0f; - for (uint8_t q = 8; q--;) EEPROM_WRITE(dummy); - #else - dummy = 0.0f; - for (uint8_t q = 9; q--;) EEPROM_WRITE(dummy); - #endif - - #if DISABLED(ULTIPANEL) - int preheatHotendTemp1 = PREHEAT_1_TEMP_HOTEND, preheatBedTemp1 = PREHEAT_1_TEMP_BED, preheatFanSpeed1 = PREHEAT_1_FAN_SPEED, - preheatHotendTemp2 = PREHEAT_2_TEMP_HOTEND, preheatBedTemp2 = PREHEAT_2_TEMP_BED, preheatFanSpeed2 = PREHEAT_2_FAN_SPEED; - #endif // !ULTIPANEL - - EEPROM_WRITE(preheatHotendTemp1); - EEPROM_WRITE(preheatBedTemp1); - EEPROM_WRITE(preheatFanSpeed1); - EEPROM_WRITE(preheatHotendTemp2); - EEPROM_WRITE(preheatBedTemp2); - EEPROM_WRITE(preheatFanSpeed2); - - for (uint8_t e = 0; e < MAX_EXTRUDERS; e++) { - - #if ENABLED(PIDTEMP) - if (e < HOTENDS) { - EEPROM_WRITE(PID_PARAM(Kp, e)); - EEPROM_WRITE(PID_PARAM(Ki, e)); - EEPROM_WRITE(PID_PARAM(Kd, e)); - #if ENABLED(PID_EXTRUSION_SCALING) - EEPROM_WRITE(PID_PARAM(Kc, e)); - #else - dummy = 1.0f; // 1.0 = default kc - EEPROM_WRITE(dummy); - #endif - } - else - #endif // !PIDTEMP - { - dummy = DUMMY_PID_VALUE; // When read, will not change the existing value - EEPROM_WRITE(dummy); // Kp - dummy = 0.0f; - for (uint8_t q = 3; q--;) EEPROM_WRITE(dummy); // Ki, Kd, Kc - } - - } // Hotends Loop - - #if DISABLED(PID_EXTRUSION_SCALING) - int lpq_len = 20; - #endif - EEPROM_WRITE(lpq_len); - - #if DISABLED(PIDTEMPBED) - dummy = DUMMY_PID_VALUE; - for (uint8_t q = 3; q--;) EEPROM_WRITE(dummy); - #else - EEPROM_WRITE(thermalManager.bedKp); - EEPROM_WRITE(thermalManager.bedKi); - EEPROM_WRITE(thermalManager.bedKd); - #endif - - #if !HAS_LCD_CONTRAST - const int lcd_contrast = 32; - #endif - EEPROM_WRITE(lcd_contrast); - - #if ENABLED(SCARA) - EEPROM_WRITE(axis_scaling); // 3 floats - #else - dummy = 1.0f; - EEPROM_WRITE(dummy); - #endif - - #if ENABLED(FWRETRACT) - EEPROM_WRITE(autoretract_enabled); - EEPROM_WRITE(retract_length); - #if EXTRUDERS > 1 - EEPROM_WRITE(retract_length_swap); - #else - dummy = 0.0f; - EEPROM_WRITE(dummy); + #if HOTENDS > 1 + // Skip hotend 0 which must be 0 + for (uint8_t e = 1; e < HOTENDS; e++) + LOOP_XYZ(i) EEPROM_WRITE(hotend_offset[i][e]); #endif - EEPROM_WRITE(retract_feedrate_mm_s); - EEPROM_WRITE(retract_zlift); - EEPROM_WRITE(retract_recover_length); - #if EXTRUDERS > 1 - EEPROM_WRITE(retract_recover_length_swap); - #else - dummy = 0.0f; - EEPROM_WRITE(dummy); - #endif - EEPROM_WRITE(retract_recover_feedrate_mm_s); - #endif // FWRETRACT - EEPROM_WRITE(volumetric_enabled); - - // Save filament sizes - for (uint8_t q = 0; q < MAX_EXTRUDERS; q++) { - if (q < COUNT(filament_size)) dummy = filament_size[q]; - EEPROM_WRITE(dummy); - } - - uint16_t final_checksum = eeprom_checksum, - eeprom_size = eeprom_index; - - eeprom_index = EEPROM_OFFSET; - EEPROM_WRITE(version); - EEPROM_WRITE(final_checksum); - - // Report storage size - SERIAL_ECHO_START; - SERIAL_ECHOPAIR("Settings Stored (", eeprom_size); - SERIAL_ECHOLNPGM(" bytes)"); -} - -/** - * M501 - Retrieve Configuration - */ -void Config_RetrieveSettings() { - - EEPROM_START(); - - char stored_ver[4]; - EEPROM_READ(stored_ver); - - uint16_t stored_checksum; - EEPROM_READ(stored_checksum); - - // SERIAL_ECHOPAIR("Version: [", ver); - // SERIAL_ECHOPAIR("] Stored version: [", stored_ver); - // SERIAL_ECHOLNPGM("]"); - - if (strncmp(version, stored_ver, 3) != 0) { - Config_ResetDefault(); - } - else { - float dummy = 0; - - eeprom_checksum = 0; // clear before reading first "real data" - - // version number match - EEPROM_READ(planner.axis_steps_per_mm); - EEPROM_READ(planner.max_feedrate_mm_s); - EEPROM_READ(planner.max_acceleration_mm_per_s2); - - EEPROM_READ(planner.acceleration); - EEPROM_READ(planner.retract_acceleration); - EEPROM_READ(planner.travel_acceleration); - EEPROM_READ(planner.min_feedrate_mm_s); - EEPROM_READ(planner.min_travel_feedrate_mm_s); - EEPROM_READ(planner.min_segment_time); - EEPROM_READ(planner.max_xy_jerk); - EEPROM_READ(planner.max_z_jerk); - EEPROM_READ(planner.max_e_jerk); - EEPROM_READ(home_offset); - - uint8_t dummy_uint8 = 0, mesh_num_x = 0, mesh_num_y = 0; - EEPROM_READ(dummy_uint8); - EEPROM_READ(dummy); - EEPROM_READ(mesh_num_x); - EEPROM_READ(mesh_num_y); #if ENABLED(MESH_BED_LEVELING) - mbl.status = dummy_uint8; - mbl.z_offset = dummy; - if (mesh_num_x == MESH_NUM_X_POINTS && mesh_num_y == MESH_NUM_Y_POINTS) { - // EEPROM data fits the current mesh - EEPROM_READ(mbl.z_values); - } - else { - // EEPROM data is stale - mbl.reset(); - for (uint8_t q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_READ(dummy); - } + // Compile time test that sizeof(mbl.z_values) is as expected + typedef char c_assert[(sizeof(mbl.z_values) == (MESH_NUM_X_POINTS) * (MESH_NUM_Y_POINTS) * sizeof(dummy)) ? 1 : -1]; + uint8_t mesh_num_x = MESH_NUM_X_POINTS, + mesh_num_y = MESH_NUM_Y_POINTS, + dummy_uint8 = mbl.status & _BV(MBL_STATUS_HAS_MESH_BIT); + EEPROM_WRITE(dummy_uint8); + EEPROM_WRITE(mbl.z_offset); + EEPROM_WRITE(mesh_num_x); + EEPROM_WRITE(mesh_num_y); + EEPROM_WRITE(mbl.z_values); #else - // MBL is disabled - skip the stored data - for (uint8_t q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_READ(dummy); + // For disabled MBL write a default mesh + uint8_t mesh_num_x = 3, + mesh_num_y = 3, + dummy_uint8 = 0; + dummy = 0.0f; + EEPROM_WRITE(dummy_uint8); + EEPROM_WRITE(dummy); + EEPROM_WRITE(mesh_num_x); + EEPROM_WRITE(mesh_num_y); + for (uint8_t q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_WRITE(dummy); #endif // MESH_BED_LEVELING #if !HAS_BED_PROBE float zprobe_zoffset = 0; #endif - EEPROM_READ(zprobe_zoffset); + EEPROM_WRITE(zprobe_zoffset); + // 9 floats for DELTA / Z_DUAL_ENDSTOPS #if ENABLED(DELTA) - EEPROM_READ(endstop_adj); // 3 floats - EEPROM_READ(delta_radius); // 1 float - EEPROM_READ(delta_diagonal_rod); // 1 float - EEPROM_READ(delta_segments_per_second); // 1 float - EEPROM_READ(delta_diagonal_rod_trim_tower_1); // 1 float - EEPROM_READ(delta_diagonal_rod_trim_tower_2); // 1 float - EEPROM_READ(delta_diagonal_rod_trim_tower_3); // 1 float + EEPROM_WRITE(endstop_adj); // 3 floats + EEPROM_WRITE(delta_radius); // 1 float + EEPROM_WRITE(delta_diagonal_rod); // 1 float + EEPROM_WRITE(delta_segments_per_second); // 1 float + EEPROM_WRITE(delta_diagonal_rod_trim_tower_1); // 1 float + EEPROM_WRITE(delta_diagonal_rod_trim_tower_2); // 1 float + EEPROM_WRITE(delta_diagonal_rod_trim_tower_3); // 1 float #elif ENABLED(Z_DUAL_ENDSTOPS) - EEPROM_READ(z_endstop_adj); + EEPROM_WRITE(z_endstop_adj); // 1 float dummy = 0.0f; - for (uint8_t q=8; q--;) EEPROM_READ(dummy); + for (uint8_t q = 8; q--;) EEPROM_WRITE(dummy); #else dummy = 0.0f; - for (uint8_t q=9; q--;) EEPROM_READ(dummy); + for (uint8_t q = 9; q--;) EEPROM_WRITE(dummy); #endif #if DISABLED(ULTIPANEL) - int preheatHotendTemp1, preheatBedTemp1, preheatFanSpeed1, - preheatHotendTemp2, preheatBedTemp2, preheatFanSpeed2; - #endif + const int lcd_preheat_hotend_temp[2] = { PREHEAT_1_TEMP_HOTEND, PREHEAT_2_TEMP_HOTEND }, + lcd_preheat_bed_temp[2] = { PREHEAT_1_TEMP_BED, PREHEAT_2_TEMP_BED }, + lcd_preheat_fan_speed[2] = { PREHEAT_1_FAN_SPEED, PREHEAT_2_FAN_SPEED }; + #endif // !ULTIPANEL - EEPROM_READ(preheatHotendTemp1); - EEPROM_READ(preheatBedTemp1); - EEPROM_READ(preheatFanSpeed1); - EEPROM_READ(preheatHotendTemp2); - EEPROM_READ(preheatBedTemp2); - EEPROM_READ(preheatFanSpeed2); + EEPROM_WRITE(lcd_preheat_hotend_temp); + EEPROM_WRITE(lcd_preheat_bed_temp); + EEPROM_WRITE(lcd_preheat_fan_speed); - #if ENABLED(PIDTEMP) - for (uint8_t e = 0; e < MAX_EXTRUDERS; e++) { - EEPROM_READ(dummy); // Kp - if (e < HOTENDS && dummy != DUMMY_PID_VALUE) { - // do not need to scale PID values as the values in EEPROM are already scaled - PID_PARAM(Kp, e) = dummy; - EEPROM_READ(PID_PARAM(Ki, e)); - EEPROM_READ(PID_PARAM(Kd, e)); + for (uint8_t e = 0; e < MAX_EXTRUDERS; e++) { + + #if ENABLED(PIDTEMP) + if (e < HOTENDS) { + EEPROM_WRITE(PID_PARAM(Kp, e)); + EEPROM_WRITE(PID_PARAM(Ki, e)); + EEPROM_WRITE(PID_PARAM(Kd, e)); #if ENABLED(PID_EXTRUSION_SCALING) - EEPROM_READ(PID_PARAM(Kc, e)); + EEPROM_WRITE(PID_PARAM(Kc, e)); #else - EEPROM_READ(dummy); + dummy = 1.0f; // 1.0 = default kc + EEPROM_WRITE(dummy); #endif } - else { - for (uint8_t q=3; q--;) EEPROM_READ(dummy); // Ki, Kd, Kc + else + #endif // !PIDTEMP + { + dummy = DUMMY_PID_VALUE; // When read, will not change the existing value + EEPROM_WRITE(dummy); // Kp + dummy = 0.0f; + for (uint8_t q = 3; q--;) EEPROM_WRITE(dummy); // Ki, Kd, Kc } - } - #else // !PIDTEMP - // 4 x 4 = 16 slots for PID parameters - for (uint8_t q = MAX_EXTRUDERS * 4; q--;) EEPROM_READ(dummy); // Kp, Ki, Kd, Kc - #endif // !PIDTEMP + + } // Hotends Loop #if DISABLED(PID_EXTRUSION_SCALING) - int lpq_len; + int lpq_len = 20; #endif - EEPROM_READ(lpq_len); + EEPROM_WRITE(lpq_len); - #if ENABLED(PIDTEMPBED) - EEPROM_READ(dummy); // bedKp - if (dummy != DUMMY_PID_VALUE) { - thermalManager.bedKp = dummy; - EEPROM_READ(thermalManager.bedKi); - EEPROM_READ(thermalManager.bedKd); - } + #if DISABLED(PIDTEMPBED) + dummy = DUMMY_PID_VALUE; + for (uint8_t q = 3; q--;) EEPROM_WRITE(dummy); #else - for (uint8_t q=3; q--;) EEPROM_READ(dummy); // bedKp, bedKi, bedKd + EEPROM_WRITE(thermalManager.bedKp); + EEPROM_WRITE(thermalManager.bedKi); + EEPROM_WRITE(thermalManager.bedKd); #endif #if !HAS_LCD_CONTRAST - int lcd_contrast; - #endif - EEPROM_READ(lcd_contrast); - - #if ENABLED(SCARA) - EEPROM_READ(axis_scaling); // 3 floats - #else - EEPROM_READ(dummy); + const int lcd_contrast = 32; #endif + EEPROM_WRITE(lcd_contrast); #if ENABLED(FWRETRACT) - EEPROM_READ(autoretract_enabled); - EEPROM_READ(retract_length); + EEPROM_WRITE(autoretract_enabled); + EEPROM_WRITE(retract_length); #if EXTRUDERS > 1 - EEPROM_READ(retract_length_swap); + EEPROM_WRITE(retract_length_swap); #else - EEPROM_READ(dummy); + dummy = 0.0f; + EEPROM_WRITE(dummy); #endif - EEPROM_READ(retract_feedrate_mm_s); - EEPROM_READ(retract_zlift); - EEPROM_READ(retract_recover_length); + EEPROM_WRITE(retract_feedrate_mm_s); + EEPROM_WRITE(retract_zlift); + EEPROM_WRITE(retract_recover_length); #if EXTRUDERS > 1 - EEPROM_READ(retract_recover_length_swap); + EEPROM_WRITE(retract_recover_length_swap); #else - EEPROM_READ(dummy); + dummy = 0.0f; + EEPROM_WRITE(dummy); #endif - EEPROM_READ(retract_recover_feedrate_mm_s); + EEPROM_WRITE(retract_recover_feedrate_mm_s); #endif // FWRETRACT - EEPROM_READ(volumetric_enabled); + EEPROM_WRITE(volumetric_enabled); + // Save filament sizes for (uint8_t q = 0; q < MAX_EXTRUDERS; q++) { - EEPROM_READ(dummy); - if (q < COUNT(filament_size)) filament_size[q] = dummy; + if (q < COUNT(filament_size)) dummy = filament_size[q]; + EEPROM_WRITE(dummy); } - if (eeprom_checksum == stored_checksum) { - Config_Postprocess(); - SERIAL_ECHO_START; - SERIAL_ECHO(version); - SERIAL_ECHOPAIR(" stored settings retrieved (", eeprom_index); - SERIAL_ECHOLNPGM(" bytes)"); - } - else { - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM("EEPROM checksum mismatch"); + uint16_t final_checksum = eeprom_checksum, + eeprom_size = eeprom_index; + + eeprom_index = EEPROM_OFFSET; + EEPROM_WRITE(version); + EEPROM_WRITE(final_checksum); + + // Report storage size + SERIAL_ECHO_START; + SERIAL_ECHOPAIR("Settings Stored (", eeprom_size); + SERIAL_ECHOLNPGM(" bytes)"); + } + + /** + * M501 - Retrieve Configuration + */ + void Config_RetrieveSettings() { + + EEPROM_START(); + + char stored_ver[4]; + EEPROM_READ(stored_ver); + + uint16_t stored_checksum; + EEPROM_READ(stored_checksum); + + // SERIAL_ECHOPAIR("Version: [", ver); + // SERIAL_ECHOPAIR("] Stored version: [", stored_ver); + // SERIAL_CHAR(']'); + // SERIAL_EOL; + + if (strncmp(version, stored_ver, 3) != 0) { Config_ResetDefault(); } - } + else { + float dummy = 0; - #if ENABLED(EEPROM_CHITCHAT) - Config_PrintSettings(); - #endif -} + eeprom_checksum = 0; // clear before reading first "real data" -#endif // EEPROM_SETTINGS + // version number match + EEPROM_READ(planner.axis_steps_per_mm); + EEPROM_READ(planner.max_feedrate_mm_s); + EEPROM_READ(planner.max_acceleration_mm_per_s2); + + EEPROM_READ(planner.acceleration); + EEPROM_READ(planner.retract_acceleration); + EEPROM_READ(planner.travel_acceleration); + EEPROM_READ(planner.min_feedrate_mm_s); + EEPROM_READ(planner.min_travel_feedrate_mm_s); + EEPROM_READ(planner.min_segment_time); + EEPROM_READ(planner.max_jerk); + EEPROM_READ(home_offset); + + #if HOTENDS > 1 + // Skip hotend 0 which must be 0 + for (uint8_t e = 1; e < HOTENDS; e++) + LOOP_XYZ(i) EEPROM_READ(hotend_offset[i][e]); + #endif + + uint8_t dummy_uint8 = 0, mesh_num_x = 0, mesh_num_y = 0; + EEPROM_READ(dummy_uint8); + EEPROM_READ(dummy); + EEPROM_READ(mesh_num_x); + EEPROM_READ(mesh_num_y); + #if ENABLED(MESH_BED_LEVELING) + mbl.status = dummy_uint8; + mbl.z_offset = dummy; + if (mesh_num_x == MESH_NUM_X_POINTS && mesh_num_y == MESH_NUM_Y_POINTS) { + // EEPROM data fits the current mesh + EEPROM_READ(mbl.z_values); + } + else { + // EEPROM data is stale + mbl.reset(); + for (uint8_t q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_READ(dummy); + } + #else + // MBL is disabled - skip the stored data + for (uint8_t q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_READ(dummy); + #endif // MESH_BED_LEVELING + + #if !HAS_BED_PROBE + float zprobe_zoffset = 0; + #endif + EEPROM_READ(zprobe_zoffset); + + #if ENABLED(DELTA) + EEPROM_READ(endstop_adj); // 3 floats + EEPROM_READ(delta_radius); // 1 float + EEPROM_READ(delta_diagonal_rod); // 1 float + EEPROM_READ(delta_segments_per_second); // 1 float + EEPROM_READ(delta_diagonal_rod_trim_tower_1); // 1 float + EEPROM_READ(delta_diagonal_rod_trim_tower_2); // 1 float + EEPROM_READ(delta_diagonal_rod_trim_tower_3); // 1 float + #elif ENABLED(Z_DUAL_ENDSTOPS) + EEPROM_READ(z_endstop_adj); + dummy = 0.0f; + for (uint8_t q=8; q--;) EEPROM_READ(dummy); + #else + dummy = 0.0f; + for (uint8_t q=9; q--;) EEPROM_READ(dummy); + #endif + + #if DISABLED(ULTIPANEL) + int lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2]; + #endif + + EEPROM_READ(lcd_preheat_hotend_temp); + EEPROM_READ(lcd_preheat_bed_temp); + EEPROM_READ(lcd_preheat_fan_speed); + + #if ENABLED(PIDTEMP) + for (uint8_t e = 0; e < MAX_EXTRUDERS; e++) { + EEPROM_READ(dummy); // Kp + if (e < HOTENDS && dummy != DUMMY_PID_VALUE) { + // do not need to scale PID values as the values in EEPROM are already scaled + PID_PARAM(Kp, e) = dummy; + EEPROM_READ(PID_PARAM(Ki, e)); + EEPROM_READ(PID_PARAM(Kd, e)); + #if ENABLED(PID_EXTRUSION_SCALING) + EEPROM_READ(PID_PARAM(Kc, e)); + #else + EEPROM_READ(dummy); + #endif + } + else { + for (uint8_t q=3; q--;) EEPROM_READ(dummy); // Ki, Kd, Kc + } + } + #else // !PIDTEMP + // 4 x 4 = 16 slots for PID parameters + for (uint8_t q = MAX_EXTRUDERS * 4; q--;) EEPROM_READ(dummy); // Kp, Ki, Kd, Kc + #endif // !PIDTEMP + + #if DISABLED(PID_EXTRUSION_SCALING) + int lpq_len; + #endif + EEPROM_READ(lpq_len); + + #if ENABLED(PIDTEMPBED) + EEPROM_READ(dummy); // bedKp + if (dummy != DUMMY_PID_VALUE) { + thermalManager.bedKp = dummy; + EEPROM_READ(thermalManager.bedKi); + EEPROM_READ(thermalManager.bedKd); + } + #else + for (uint8_t q=3; q--;) EEPROM_READ(dummy); // bedKp, bedKi, bedKd + #endif + + #if !HAS_LCD_CONTRAST + int lcd_contrast; + #endif + EEPROM_READ(lcd_contrast); + + #if ENABLED(FWRETRACT) + EEPROM_READ(autoretract_enabled); + EEPROM_READ(retract_length); + #if EXTRUDERS > 1 + EEPROM_READ(retract_length_swap); + #else + EEPROM_READ(dummy); + #endif + EEPROM_READ(retract_feedrate_mm_s); + EEPROM_READ(retract_zlift); + EEPROM_READ(retract_recover_length); + #if EXTRUDERS > 1 + EEPROM_READ(retract_recover_length_swap); + #else + EEPROM_READ(dummy); + #endif + EEPROM_READ(retract_recover_feedrate_mm_s); + #endif // FWRETRACT + + EEPROM_READ(volumetric_enabled); + + for (uint8_t q = 0; q < MAX_EXTRUDERS; q++) { + EEPROM_READ(dummy); + if (q < COUNT(filament_size)) filament_size[q] = dummy; + } + + if (eeprom_checksum == stored_checksum) { + Config_Postprocess(); + SERIAL_ECHO_START; + SERIAL_ECHO(version); + SERIAL_ECHOPAIR(" stored settings retrieved (", eeprom_index); + SERIAL_ECHOLNPGM(" bytes)"); + } + else { + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("EEPROM checksum mismatch"); + Config_ResetDefault(); + } + } + + #if ENABLED(EEPROM_CHITCHAT) + Config_PrintSettings(); + #endif + } + +#else // !EEPROM_SETTINGS + + void Config_StoreSettings() { + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("EEPROM disabled"); + } + +#endif // !EEPROM_SETTINGS /** * M502 - Reset Configuration */ void Config_ResetDefault() { - float tmp1[] = DEFAULT_AXIS_STEPS_PER_UNIT; - float tmp2[] = DEFAULT_MAX_FEEDRATE; - long tmp3[] = DEFAULT_MAX_ACCELERATION; - LOOP_XYZE(i) { - planner.axis_steps_per_mm[i] = tmp1[i]; - planner.max_feedrate_mm_s[i] = tmp2[i]; - planner.max_acceleration_mm_per_s2[i] = tmp3[i]; - #if ENABLED(SCARA) - if (i < COUNT(axis_scaling)) - axis_scaling[i] = 1; - #endif + const float tmp1[] = DEFAULT_AXIS_STEPS_PER_UNIT, tmp2[] = DEFAULT_MAX_FEEDRATE; + const long tmp3[] = DEFAULT_MAX_ACCELERATION; + LOOP_XYZE_N(i) { + planner.axis_steps_per_mm[i] = tmp1[i < COUNT(tmp1) ? i : COUNT(tmp1) - 1]; + planner.max_feedrate_mm_s[i] = tmp2[i < COUNT(tmp2) ? i : COUNT(tmp2) - 1]; + planner.max_acceleration_mm_per_s2[i] = tmp3[i < COUNT(tmp3) ? i : COUNT(tmp3) - 1]; } planner.acceleration = DEFAULT_ACCELERATION; @@ -593,11 +583,29 @@ void Config_ResetDefault() { planner.min_feedrate_mm_s = DEFAULT_MINIMUMFEEDRATE; planner.min_segment_time = DEFAULT_MINSEGMENTTIME; planner.min_travel_feedrate_mm_s = DEFAULT_MINTRAVELFEEDRATE; - planner.max_xy_jerk = DEFAULT_XYJERK; - planner.max_z_jerk = DEFAULT_ZJERK; - planner.max_e_jerk = DEFAULT_EJERK; + planner.max_jerk[X_AXIS] = DEFAULT_XJERK; + planner.max_jerk[Y_AXIS] = DEFAULT_YJERK; + planner.max_jerk[Z_AXIS] = DEFAULT_ZJERK; + planner.max_jerk[E_AXIS] = DEFAULT_EJERK; home_offset[X_AXIS] = home_offset[Y_AXIS] = home_offset[Z_AXIS] = 0; + #if HOTENDS > 1 + constexpr float tmp4[XYZ][HOTENDS] = { + HOTEND_OFFSET_X, + HOTEND_OFFSET_Y + #ifdef HOTEND_OFFSET_Z + , HOTEND_OFFSET_Z + #else + , { 0 } + #endif + }; + static_assert( + tmp4[X_AXIS][0] == 0 && tmp4[Y_AXIS][0] == 0 && tmp4[Z_AXIS][0] == 0, + "Offsets for the first hotend must be 0.0." + ); + LOOP_XYZ(i) HOTEND_LOOP() hotend_offset[i][e] = tmp4[i][e]; + #endif + #if ENABLED(MESH_BED_LEVELING) mbl.reset(); #endif @@ -607,7 +615,10 @@ void Config_ResetDefault() { #endif #if ENABLED(DELTA) - endstop_adj[X_AXIS] = endstop_adj[Y_AXIS] = endstop_adj[Z_AXIS] = 0; + const float adj[ABC] = DELTA_ENDSTOP_ADJ; + endstop_adj[A_AXIS] = adj[A_AXIS]; + endstop_adj[B_AXIS] = adj[B_AXIS]; + endstop_adj[C_AXIS] = adj[C_AXIS]; delta_radius = DELTA_RADIUS; delta_diagonal_rod = DELTA_DIAGONAL_ROD; delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND; @@ -619,12 +630,12 @@ void Config_ResetDefault() { #endif #if ENABLED(ULTIPANEL) - preheatHotendTemp1 = PREHEAT_1_TEMP_HOTEND; - preheatBedTemp1 = PREHEAT_1_TEMP_BED; - preheatFanSpeed1 = PREHEAT_1_FAN_SPEED; - preheatHotendTemp2 = PREHEAT_2_TEMP_HOTEND; - preheatBedTemp2 = PREHEAT_2_TEMP_BED; - preheatFanSpeed2 = PREHEAT_2_FAN_SPEED; + lcd_preheat_hotend_temp[0] = PREHEAT_1_TEMP_HOTEND; + lcd_preheat_hotend_temp[1] = PREHEAT_2_TEMP_HOTEND; + lcd_preheat_bed_temp[0] = PREHEAT_1_TEMP_BED; + lcd_preheat_bed_temp[1] = PREHEAT_2_TEMP_BED; + lcd_preheat_fan_speed[0] = PREHEAT_1_FAN_SPEED; + lcd_preheat_fan_speed[1] = PREHEAT_2_FAN_SPEED; #endif #if HAS_LCD_CONTRAST @@ -691,304 +702,333 @@ void Config_ResetDefault() { #if DISABLED(DISABLE_M503) -#define CONFIG_ECHO_START do{ if (!forReplay) SERIAL_ECHO_START; }while(0) + #define CONFIG_ECHO_START do{ if (!forReplay) SERIAL_ECHO_START; }while(0) -/** - * M503 - Print Configuration - */ -void Config_PrintSettings(bool forReplay) { - // Always have this function, even with EEPROM_SETTINGS disabled, the current values will be shown + /** + * M503 - Print Configuration + */ + void Config_PrintSettings(bool forReplay) { + // Always have this function, even with EEPROM_SETTINGS disabled, the current values will be shown - CONFIG_ECHO_START; - - if (!forReplay) { - SERIAL_ECHOLNPGM("Steps per unit:"); CONFIG_ECHO_START; - } - SERIAL_ECHOPAIR(" M92 X", planner.axis_steps_per_mm[X_AXIS]); - SERIAL_ECHOPAIR(" Y", planner.axis_steps_per_mm[Y_AXIS]); - SERIAL_ECHOPAIR(" Z", planner.axis_steps_per_mm[Z_AXIS]); - SERIAL_ECHOPAIR(" E", planner.axis_steps_per_mm[E_AXIS]); - SERIAL_EOL; - CONFIG_ECHO_START; - - #if ENABLED(SCARA) if (!forReplay) { - SERIAL_ECHOLNPGM("Scaling factors:"); + SERIAL_ECHOLNPGM("Steps per unit:"); CONFIG_ECHO_START; } - SERIAL_ECHOPAIR(" M365 X", axis_scaling[X_AXIS]); - SERIAL_ECHOPAIR(" Y", axis_scaling[Y_AXIS]); - SERIAL_ECHOPAIR(" Z", axis_scaling[Z_AXIS]); + SERIAL_ECHOPAIR(" M92 X", planner.axis_steps_per_mm[X_AXIS]); + SERIAL_ECHOPAIR(" Y", planner.axis_steps_per_mm[Y_AXIS]); + SERIAL_ECHOPAIR(" Z", planner.axis_steps_per_mm[Z_AXIS]); + #if E_STEPPERS == 1 + SERIAL_ECHOPAIR(" E", planner.axis_steps_per_mm[E_AXIS]); + #endif SERIAL_EOL; - CONFIG_ECHO_START; - #endif // SCARA - - if (!forReplay) { - SERIAL_ECHOLNPGM("Maximum feedrates (mm/s):"); - CONFIG_ECHO_START; - } - SERIAL_ECHOPAIR(" M203 X", planner.max_feedrate_mm_s[X_AXIS]); - SERIAL_ECHOPAIR(" Y", planner.max_feedrate_mm_s[Y_AXIS]); - SERIAL_ECHOPAIR(" Z", planner.max_feedrate_mm_s[Z_AXIS]); - SERIAL_ECHOPAIR(" E", planner.max_feedrate_mm_s[E_AXIS]); - SERIAL_EOL; - - CONFIG_ECHO_START; - if (!forReplay) { - SERIAL_ECHOLNPGM("Maximum Acceleration (mm/s2):"); - CONFIG_ECHO_START; - } - SERIAL_ECHOPAIR(" M201 X", planner.max_acceleration_mm_per_s2[X_AXIS]); - SERIAL_ECHOPAIR(" Y", planner.max_acceleration_mm_per_s2[Y_AXIS]); - SERIAL_ECHOPAIR(" Z", planner.max_acceleration_mm_per_s2[Z_AXIS]); - SERIAL_ECHOPAIR(" E", planner.max_acceleration_mm_per_s2[E_AXIS]); - SERIAL_EOL; - CONFIG_ECHO_START; - if (!forReplay) { - SERIAL_ECHOLNPGM("Accelerations: P=printing, R=retract and T=travel"); - CONFIG_ECHO_START; - } - SERIAL_ECHOPAIR(" M204 P", planner.acceleration); - SERIAL_ECHOPAIR(" R", planner.retract_acceleration); - SERIAL_ECHOPAIR(" T", planner.travel_acceleration); - SERIAL_EOL; - - CONFIG_ECHO_START; - if (!forReplay) { - SERIAL_ECHOLNPGM("Advanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum XY jerk (mm/s), Z=maximum Z jerk (mm/s), E=maximum E jerk (mm/s)"); - CONFIG_ECHO_START; - } - SERIAL_ECHOPAIR(" M205 S", planner.min_feedrate_mm_s); - SERIAL_ECHOPAIR(" T", planner.min_travel_feedrate_mm_s); - SERIAL_ECHOPAIR(" B", planner.min_segment_time); - SERIAL_ECHOPAIR(" X", planner.max_xy_jerk); - SERIAL_ECHOPAIR(" Z", planner.max_z_jerk); - SERIAL_ECHOPAIR(" E", planner.max_e_jerk); - SERIAL_EOL; - - CONFIG_ECHO_START; - if (!forReplay) { - SERIAL_ECHOLNPGM("Home offset (mm)"); - CONFIG_ECHO_START; - } - SERIAL_ECHOPAIR(" M206 X", home_offset[X_AXIS]); - SERIAL_ECHOPAIR(" Y", home_offset[Y_AXIS]); - SERIAL_ECHOPAIR(" Z", home_offset[Z_AXIS]); - SERIAL_EOL; - - #if ENABLED(MESH_BED_LEVELING) - if (!forReplay) { - SERIAL_ECHOLNPGM("Mesh bed leveling:"); - CONFIG_ECHO_START; - } - SERIAL_ECHOPAIR(" M420 S", mbl.has_mesh() ? 1 : 0); - SERIAL_ECHOPAIR(" X", MESH_NUM_X_POINTS); - SERIAL_ECHOPAIR(" Y", MESH_NUM_Y_POINTS); - SERIAL_EOL; - for (uint8_t py = 1; py <= MESH_NUM_Y_POINTS; py++) { - for (uint8_t px = 1; px <= MESH_NUM_X_POINTS; px++) { - CONFIG_ECHO_START; - SERIAL_ECHOPAIR(" G29 S3 X", px); - SERIAL_ECHOPAIR(" Y", py); - SERIAL_ECHOPGM(" Z"); - SERIAL_PROTOCOL_F(mbl.z_values[py-1][px-1], 5); - SERIAL_EOL; + #if ENABLED(DISTINCT_E_FACTORS) + for (uint8_t i = 0; i < E_STEPPERS; i++) { + SERIAL_ECHOPAIR(" M92 T", (int)i); + SERIAL_ECHOLNPAIR(" E", planner.axis_steps_per_mm[E_AXIS + i]); } - } - #endif + #endif - #if ENABLED(DELTA) CONFIG_ECHO_START; - if (!forReplay) { - SERIAL_ECHOLNPGM("Endstop adjustment (mm):"); - CONFIG_ECHO_START; - } - SERIAL_ECHOPAIR(" M666 X", endstop_adj[X_AXIS]); - SERIAL_ECHOPAIR(" Y", endstop_adj[Y_AXIS]); - SERIAL_ECHOPAIR(" Z", endstop_adj[Z_AXIS]); - SERIAL_EOL; - CONFIG_ECHO_START; - if (!forReplay) { - SERIAL_ECHOLNPGM("Delta settings: L=diagonal_rod, R=radius, S=segments_per_second, ABC=diagonal_rod_trim_tower_[123]"); - CONFIG_ECHO_START; - } - SERIAL_ECHOPAIR(" M665 L", delta_diagonal_rod); - SERIAL_ECHOPAIR(" R", delta_radius); - SERIAL_ECHOPAIR(" S", delta_segments_per_second); - SERIAL_ECHOPAIR(" A", delta_diagonal_rod_trim_tower_1); - SERIAL_ECHOPAIR(" B", delta_diagonal_rod_trim_tower_2); - SERIAL_ECHOPAIR(" C", delta_diagonal_rod_trim_tower_3); - SERIAL_EOL; - #elif ENABLED(Z_DUAL_ENDSTOPS) - CONFIG_ECHO_START; - if (!forReplay) { - SERIAL_ECHOLNPGM("Z2 Endstop adjustment (mm):"); - CONFIG_ECHO_START; - } - SERIAL_ECHOPAIR(" M666 Z", z_endstop_adj); - SERIAL_EOL; - #endif // DELTA - #if ENABLED(ULTIPANEL) - CONFIG_ECHO_START; if (!forReplay) { - SERIAL_ECHOLNPGM("Material heatup parameters:"); + SERIAL_ECHOLNPGM("Maximum feedrates (mm/s):"); CONFIG_ECHO_START; } - SERIAL_ECHOPAIR(" M145 S0 H", preheatHotendTemp1); - SERIAL_ECHOPAIR(" B", preheatBedTemp1); - SERIAL_ECHOPAIR(" F", preheatFanSpeed1); + SERIAL_ECHOPAIR(" M203 X", planner.max_feedrate_mm_s[X_AXIS]); + SERIAL_ECHOPAIR(" Y", planner.max_feedrate_mm_s[Y_AXIS]); + SERIAL_ECHOPAIR(" Z", planner.max_feedrate_mm_s[Z_AXIS]); + #if E_STEPPERS == 1 + SERIAL_ECHOPAIR(" E", planner.max_feedrate_mm_s[E_AXIS]); + #endif SERIAL_EOL; - CONFIG_ECHO_START; - SERIAL_ECHOPAIR(" M145 S1 H", preheatHotendTemp2); - SERIAL_ECHOPAIR(" B", preheatBedTemp2); - SERIAL_ECHOPAIR(" F", preheatFanSpeed2); - SERIAL_EOL; - #endif // ULTIPANEL - - #if HAS_PID_HEATING + #if ENABLED(DISTINCT_E_FACTORS) + for (uint8_t i = 0; i < E_STEPPERS; i++) { + SERIAL_ECHOPAIR(" M203 T", (int)i); + SERIAL_ECHOLNPAIR(" E", planner.max_feedrate_mm_s[E_AXIS + i]); + } + #endif CONFIG_ECHO_START; if (!forReplay) { - SERIAL_ECHOLNPGM("PID settings:"); + SERIAL_ECHOLNPGM("Maximum Acceleration (mm/s2):"); + CONFIG_ECHO_START; } - #if ENABLED(PIDTEMP) - #if HOTENDS > 1 - if (forReplay) { - HOTEND_LOOP() { - CONFIG_ECHO_START; - SERIAL_ECHOPAIR(" M301 E", e); - SERIAL_ECHOPAIR(" P", PID_PARAM(Kp, e)); - SERIAL_ECHOPAIR(" I", unscalePID_i(PID_PARAM(Ki, e))); - SERIAL_ECHOPAIR(" D", unscalePID_d(PID_PARAM(Kd, e))); - #if ENABLED(PID_EXTRUSION_SCALING) - SERIAL_ECHOPAIR(" C", PID_PARAM(Kc, e)); - if (e == 0) SERIAL_ECHOPAIR(" L", lpq_len); - #endif - SERIAL_EOL; - } - } - else - #endif // HOTENDS > 1 - // !forReplay || HOTENDS == 1 - { + SERIAL_ECHOPAIR(" M201 X", planner.max_acceleration_mm_per_s2[X_AXIS]); + SERIAL_ECHOPAIR(" Y", planner.max_acceleration_mm_per_s2[Y_AXIS]); + SERIAL_ECHOPAIR(" Z", planner.max_acceleration_mm_per_s2[Z_AXIS]); + #if E_STEPPERS == 1 + SERIAL_ECHOPAIR(" E", planner.max_acceleration_mm_per_s2[E_AXIS]); + #endif + SERIAL_EOL; + #if ENABLED(DISTINCT_E_FACTORS) + for (uint8_t i = 0; i < E_STEPPERS; i++) { + SERIAL_ECHOPAIR(" M201 T", (int)i); + SERIAL_ECHOLNPAIR(" E", planner.max_acceleration_mm_per_s2[E_AXIS + i]); + } + #endif + + CONFIG_ECHO_START; + if (!forReplay) { + SERIAL_ECHOLNPGM("Accelerations: P=printing, R=retract and T=travel"); + CONFIG_ECHO_START; + } + SERIAL_ECHOPAIR(" M204 P", planner.acceleration); + SERIAL_ECHOPAIR(" R", planner.retract_acceleration); + SERIAL_ECHOPAIR(" T", planner.travel_acceleration); + SERIAL_EOL; + + CONFIG_ECHO_START; + if (!forReplay) { + SERIAL_ECHOLNPGM("Advanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum XY jerk (mm/s), Z=maximum Z jerk (mm/s), E=maximum E jerk (mm/s)"); + CONFIG_ECHO_START; + } + SERIAL_ECHOPAIR(" M205 S", planner.min_feedrate_mm_s); + SERIAL_ECHOPAIR(" T", planner.min_travel_feedrate_mm_s); + SERIAL_ECHOPAIR(" B", planner.min_segment_time); + SERIAL_ECHOPAIR(" X", planner.max_jerk[X_AXIS]); + SERIAL_ECHOPAIR(" Y", planner.max_jerk[Y_AXIS]); + SERIAL_ECHOPAIR(" Z", planner.max_jerk[Z_AXIS]); + SERIAL_ECHOPAIR(" E", planner.max_jerk[E_AXIS]); + SERIAL_EOL; + + CONFIG_ECHO_START; + if (!forReplay) { + SERIAL_ECHOLNPGM("Home offset (mm)"); + CONFIG_ECHO_START; + } + SERIAL_ECHOPAIR(" M206 X", home_offset[X_AXIS]); + SERIAL_ECHOPAIR(" Y", home_offset[Y_AXIS]); + SERIAL_ECHOPAIR(" Z", home_offset[Z_AXIS]); + SERIAL_EOL; + + #if HOTENDS > 1 + CONFIG_ECHO_START; + if (!forReplay) { + SERIAL_ECHOLNPGM("Hotend offsets (mm)"); CONFIG_ECHO_START; - SERIAL_ECHOPAIR(" M301 P", PID_PARAM(Kp, 0)); // for compatibility with hosts, only echo values for E0 - SERIAL_ECHOPAIR(" I", unscalePID_i(PID_PARAM(Ki, 0))); - SERIAL_ECHOPAIR(" D", unscalePID_d(PID_PARAM(Kd, 0))); - #if ENABLED(PID_EXTRUSION_SCALING) - SERIAL_ECHOPAIR(" C", PID_PARAM(Kc, 0)); - SERIAL_ECHOPAIR(" L", lpq_len); + } + for (uint8_t e = 1; e < HOTENDS; e++) { + SERIAL_ECHOPAIR(" M218 T", (int)e); + SERIAL_ECHOPAIR(" X", hotend_offset[X_AXIS][e]); + SERIAL_ECHOPAIR(" Y", hotend_offset[Y_AXIS][e]); + #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_EXTRUDER) + SERIAL_ECHOPAIR(" Z", hotend_offset[Z_AXIS][e]); #endif SERIAL_EOL; } - #endif // PIDTEMP - - #if ENABLED(PIDTEMPBED) - CONFIG_ECHO_START; - SERIAL_ECHOPAIR(" M304 P", thermalManager.bedKp); - SERIAL_ECHOPAIR(" I", unscalePID_i(thermalManager.bedKi)); - SERIAL_ECHOPAIR(" D", unscalePID_d(thermalManager.bedKd)); - SERIAL_EOL; #endif - #endif // PIDTEMP || PIDTEMPBED - - #if HAS_LCD_CONTRAST - CONFIG_ECHO_START; - if (!forReplay) { - SERIAL_ECHOLNPGM("LCD Contrast:"); - CONFIG_ECHO_START; - } - SERIAL_ECHOPAIR(" M250 C", lcd_contrast); - SERIAL_EOL; - #endif - - #if ENABLED(FWRETRACT) - - CONFIG_ECHO_START; - if (!forReplay) { - SERIAL_ECHOLNPGM("Retract: S=Length (mm) F:Speed (mm/m) Z: ZLift (mm)"); - CONFIG_ECHO_START; - } - SERIAL_ECHOPAIR(" M207 S", retract_length); - #if EXTRUDERS > 1 - SERIAL_ECHOPAIR(" W", retract_length_swap); - #endif - SERIAL_ECHOPAIR(" F", MMS_TO_MMM(retract_feedrate_mm_s)); - SERIAL_ECHOPAIR(" Z", retract_zlift); - SERIAL_EOL; - CONFIG_ECHO_START; - if (!forReplay) { - SERIAL_ECHOLNPGM("Recover: S=Extra length (mm) F:Speed (mm/m)"); - CONFIG_ECHO_START; - } - SERIAL_ECHOPAIR(" M208 S", retract_recover_length); - #if EXTRUDERS > 1 - SERIAL_ECHOPAIR(" W", retract_recover_length_swap); - #endif - SERIAL_ECHOPAIR(" F", MMS_TO_MMM(retract_recover_feedrate_mm_s)); - SERIAL_EOL; - CONFIG_ECHO_START; - if (!forReplay) { - SERIAL_ECHOLNPGM("Auto-Retract: S=0 to disable, 1 to interpret extrude-only moves as retracts or recoveries"); - CONFIG_ECHO_START; - } - SERIAL_ECHOPAIR(" M209 S", autoretract_enabled ? 1 : 0); - SERIAL_EOL; - - #endif // FWRETRACT - - /** - * Volumetric extrusion M200 - */ - if (!forReplay) { - CONFIG_ECHO_START; - SERIAL_ECHOPGM("Filament settings:"); - if (volumetric_enabled) - SERIAL_EOL; - else - SERIAL_ECHOLNPGM(" Disabled"); - } - - CONFIG_ECHO_START; - SERIAL_ECHOPAIR(" M200 D", filament_size[0]); - SERIAL_EOL; - #if EXTRUDERS > 1 - CONFIG_ECHO_START; - SERIAL_ECHOPAIR(" M200 T1 D", filament_size[1]); - SERIAL_EOL; - #if EXTRUDERS > 2 - CONFIG_ECHO_START; - SERIAL_ECHOPAIR(" M200 T2 D", filament_size[2]); - SERIAL_EOL; - #if EXTRUDERS > 3 + #if ENABLED(MESH_BED_LEVELING) + if (!forReplay) { + SERIAL_ECHOLNPGM("Mesh bed leveling:"); CONFIG_ECHO_START; - SERIAL_ECHOPAIR(" M200 T3 D", filament_size[3]); + } + SERIAL_ECHOPAIR(" M420 S", mbl.has_mesh() ? 1 : 0); + SERIAL_ECHOPAIR(" X", MESH_NUM_X_POINTS); + SERIAL_ECHOPAIR(" Y", MESH_NUM_Y_POINTS); + SERIAL_EOL; + for (uint8_t py = 1; py <= MESH_NUM_Y_POINTS; py++) { + for (uint8_t px = 1; px <= MESH_NUM_X_POINTS; px++) { + CONFIG_ECHO_START; + SERIAL_ECHOPAIR(" G29 S3 X", (int)px); + SERIAL_ECHOPAIR(" Y", (int)py); + SERIAL_ECHOPGM(" Z"); + SERIAL_PROTOCOL_F(mbl.z_values[py-1][px-1], 5); + SERIAL_EOL; + } + } + #endif + + #if ENABLED(DELTA) + CONFIG_ECHO_START; + if (!forReplay) { + SERIAL_ECHOLNPGM("Endstop adjustment (mm):"); + CONFIG_ECHO_START; + } + SERIAL_ECHOPAIR(" M666 X", endstop_adj[X_AXIS]); + SERIAL_ECHOPAIR(" Y", endstop_adj[Y_AXIS]); + SERIAL_ECHOPAIR(" Z", endstop_adj[Z_AXIS]); + SERIAL_EOL; + CONFIG_ECHO_START; + if (!forReplay) { + SERIAL_ECHOLNPGM("Delta settings: L=diagonal_rod, R=radius, S=segments_per_second, ABC=diagonal_rod_trim_tower_[123]"); + CONFIG_ECHO_START; + } + SERIAL_ECHOPAIR(" M665 L", delta_diagonal_rod); + SERIAL_ECHOPAIR(" R", delta_radius); + SERIAL_ECHOPAIR(" S", delta_segments_per_second); + SERIAL_ECHOPAIR(" A", delta_diagonal_rod_trim_tower_1); + SERIAL_ECHOPAIR(" B", delta_diagonal_rod_trim_tower_2); + SERIAL_ECHOPAIR(" C", delta_diagonal_rod_trim_tower_3); + SERIAL_EOL; + #elif ENABLED(Z_DUAL_ENDSTOPS) + CONFIG_ECHO_START; + if (!forReplay) { + SERIAL_ECHOLNPGM("Z2 Endstop adjustment (mm):"); + CONFIG_ECHO_START; + } + SERIAL_ECHOPAIR(" M666 Z", z_endstop_adj); + SERIAL_EOL; + #endif // DELTA + + #if ENABLED(ULTIPANEL) + CONFIG_ECHO_START; + if (!forReplay) { + SERIAL_ECHOLNPGM("Material heatup parameters:"); + CONFIG_ECHO_START; + } + for (uint8_t i = 0; i < COUNT(lcd_preheat_hotend_temp); i++) { + SERIAL_ECHOPAIR(" M145 S", (int)i); + SERIAL_ECHOPAIR(" H", lcd_preheat_hotend_temp[i]); + SERIAL_ECHOPAIR(" B", lcd_preheat_bed_temp[i]); + SERIAL_ECHOPAIR(" F", lcd_preheat_fan_speed[i]); + SERIAL_EOL; + } + #endif // ULTIPANEL + + #if HAS_PID_HEATING + + CONFIG_ECHO_START; + if (!forReplay) { + SERIAL_ECHOLNPGM("PID settings:"); + } + #if ENABLED(PIDTEMP) + #if HOTENDS > 1 + if (forReplay) { + HOTEND_LOOP() { + CONFIG_ECHO_START; + SERIAL_ECHOPAIR(" M301 E", e); + SERIAL_ECHOPAIR(" P", PID_PARAM(Kp, e)); + SERIAL_ECHOPAIR(" I", unscalePID_i(PID_PARAM(Ki, e))); + SERIAL_ECHOPAIR(" D", unscalePID_d(PID_PARAM(Kd, e))); + #if ENABLED(PID_EXTRUSION_SCALING) + SERIAL_ECHOPAIR(" C", PID_PARAM(Kc, e)); + if (e == 0) SERIAL_ECHOPAIR(" L", lpq_len); + #endif + SERIAL_EOL; + } + } + else + #endif // HOTENDS > 1 + // !forReplay || HOTENDS == 1 + { + CONFIG_ECHO_START; + SERIAL_ECHOPAIR(" M301 P", PID_PARAM(Kp, 0)); // for compatibility with hosts, only echo values for E0 + SERIAL_ECHOPAIR(" I", unscalePID_i(PID_PARAM(Ki, 0))); + SERIAL_ECHOPAIR(" D", unscalePID_d(PID_PARAM(Kd, 0))); + #if ENABLED(PID_EXTRUSION_SCALING) + SERIAL_ECHOPAIR(" C", PID_PARAM(Kc, 0)); + SERIAL_ECHOPAIR(" L", lpq_len); + #endif + SERIAL_EOL; + } + #endif // PIDTEMP + + #if ENABLED(PIDTEMPBED) + CONFIG_ECHO_START; + SERIAL_ECHOPAIR(" M304 P", thermalManager.bedKp); + SERIAL_ECHOPAIR(" I", unscalePID_i(thermalManager.bedKi)); + SERIAL_ECHOPAIR(" D", unscalePID_d(thermalManager.bedKd)); SERIAL_EOL; #endif + + #endif // PIDTEMP || PIDTEMPBED + + #if HAS_LCD_CONTRAST + CONFIG_ECHO_START; + if (!forReplay) { + SERIAL_ECHOLNPGM("LCD Contrast:"); + CONFIG_ECHO_START; + } + SERIAL_ECHOPAIR(" M250 C", lcd_contrast); + SERIAL_EOL; #endif - #endif - if (!volumetric_enabled) { - CONFIG_ECHO_START; - SERIAL_ECHOLNPGM(" M200 D0"); - } + #if ENABLED(FWRETRACT) - /** - * Auto Bed Leveling - */ - #if HAS_BED_PROBE + CONFIG_ECHO_START; + if (!forReplay) { + SERIAL_ECHOLNPGM("Retract: S=Length (mm) F:Speed (mm/m) Z: ZLift (mm)"); + CONFIG_ECHO_START; + } + SERIAL_ECHOPAIR(" M207 S", retract_length); + #if EXTRUDERS > 1 + SERIAL_ECHOPAIR(" W", retract_length_swap); + #endif + SERIAL_ECHOPAIR(" F", MMS_TO_MMM(retract_feedrate_mm_s)); + SERIAL_ECHOPAIR(" Z", retract_zlift); + SERIAL_EOL; + CONFIG_ECHO_START; + if (!forReplay) { + SERIAL_ECHOLNPGM("Recover: S=Extra length (mm) F:Speed (mm/m)"); + CONFIG_ECHO_START; + } + SERIAL_ECHOPAIR(" M208 S", retract_recover_length); + #if EXTRUDERS > 1 + SERIAL_ECHOPAIR(" W", retract_recover_length_swap); + #endif + SERIAL_ECHOPAIR(" F", MMS_TO_MMM(retract_recover_feedrate_mm_s)); + SERIAL_EOL; + CONFIG_ECHO_START; + if (!forReplay) { + SERIAL_ECHOLNPGM("Auto-Retract: S=0 to disable, 1 to interpret extrude-only moves as retracts or recoveries"); + CONFIG_ECHO_START; + } + SERIAL_ECHOPAIR(" M209 S", autoretract_enabled ? 1 : 0); + SERIAL_EOL; + + #endif // FWRETRACT + + /** + * Volumetric extrusion M200 + */ if (!forReplay) { CONFIG_ECHO_START; - SERIAL_ECHOLNPGM("Z-Probe Offset (mm):"); + SERIAL_ECHOPGM("Filament settings:"); + if (volumetric_enabled) + SERIAL_EOL; + else + SERIAL_ECHOLNPGM(" Disabled"); } + CONFIG_ECHO_START; - SERIAL_ECHOPAIR(" M851 Z", zprobe_zoffset); + SERIAL_ECHOPAIR(" M200 D", filament_size[0]); SERIAL_EOL; - #endif -} + #if EXTRUDERS > 1 + CONFIG_ECHO_START; + SERIAL_ECHOPAIR(" M200 T1 D", filament_size[1]); + SERIAL_EOL; + #if EXTRUDERS > 2 + CONFIG_ECHO_START; + SERIAL_ECHOPAIR(" M200 T2 D", filament_size[2]); + SERIAL_EOL; + #if EXTRUDERS > 3 + CONFIG_ECHO_START; + SERIAL_ECHOPAIR(" M200 T3 D", filament_size[3]); + SERIAL_EOL; + #endif + #endif + #endif + + if (!volumetric_enabled) { + CONFIG_ECHO_START; + SERIAL_ECHOLNPGM(" M200 D0"); + } + + /** + * Auto Bed Leveling + */ + #if HAS_BED_PROBE + if (!forReplay) { + CONFIG_ECHO_START; + SERIAL_ECHOLNPGM("Z-Probe Offset (mm):"); + } + CONFIG_ECHO_START; + SERIAL_ECHOPAIR(" M851 Z", zprobe_zoffset); + SERIAL_EOL; + #endif + } #endif // !DISABLE_M503 diff --git a/Marlin/configuration_store.h b/Marlin/configuration_store.h index 891f19fb97..7279dc4d57 100644 --- a/Marlin/configuration_store.h +++ b/Marlin/configuration_store.h @@ -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 diff --git a/Marlin/dac_mcp4728.cpp b/Marlin/dac_mcp4728.cpp index 01e38edf87..2124a803e0 100644 --- a/Marlin/dac_mcp4728.cpp +++ b/Marlin/dac_mcp4728.cpp @@ -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(); } diff --git a/Marlin/dac_mcp4728.h b/Marlin/dac_mcp4728.h index c096c856a9..a1e3e35503 100644 --- a/Marlin/dac_mcp4728.h +++ b/Marlin/dac_mcp4728.h @@ -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 diff --git a/Marlin/dogm_font_data_ISO10646_1_tr.h b/Marlin/dogm_font_data_ISO10646_1_tr.h new file mode 100644 index 0000000000..23d6ea88be --- /dev/null +++ b/Marlin/dogm_font_data_ISO10646_1_tr.h @@ -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 . + * + */ + +/* + 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}; diff --git a/Marlin/dogm_font_data_ISO10646_Greek.h b/Marlin/dogm_font_data_ISO10646_Greek.h index 0abb08d9dc..efe44f3cc1 100644 --- a/Marlin/dogm_font_data_ISO10646_Greek.h +++ b/Marlin/dogm_font_data_ISO10646_Greek.h @@ -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 -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}; diff --git a/Marlin/duration_t.h b/Marlin/duration_t.h index 25ea9bb989..1123b4bc4f 100644 --- a/Marlin/duration_t.h +++ b/Marlin/duration_t.h @@ -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; + } } }; diff --git a/Marlin/endstop_interrupts.h b/Marlin/endstop_interrupts.h new file mode 100644 index 0000000000..495a758f1d --- /dev/null +++ b/Marlin/endstop_interrupts.h @@ -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 . + * + */ + +/** + * 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_ diff --git a/Marlin/endstops.cpp b/Marlin/endstops.cpp index 751296d403..653e0753a9 100644 --- a/Marlin/endstops.cpp +++ b/Marlin/endstops.cpp @@ -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 diff --git a/Marlin/endstops.h b/Marlin/endstops.h index 22c2468b84..4f2ce9e5dd 100644 --- a/Marlin/endstops.h +++ b/Marlin/endstops.h @@ -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 }; diff --git a/Marlin/enum.h b/Marlin/enum.h index a51d208aee..23b1fd0339 100644 --- a/Marlin/enum.h +++ b/Marlin/enum.h @@ -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 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 + #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 + #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 diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 3e10c3f85f..6ca71feafa 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index bb8f643066..75f7a24a98 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 5700735795..da00af9d19 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 59f45c4825..ebfaff5c4c 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index feab873c4b..6d36ab0579 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index b719e60727..c70126d8e0 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index 060f4f4c98..9b506b60f1 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index eeb11da2d8..bc66b0081c 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index dbfe6b9c23..60b70eb341 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index dc26fd6039..6bb601c37e 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/K8200/README.md b/Marlin/example_configurations/K8200/README.md index bb29f51c1d..1ed6e00970 100644 --- a/Marlin/example_configurations/K8200/README.md +++ b/Marlin/example_configurations/K8200/README.md @@ -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) diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index 47ab342199..079b49e406 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index 64efac9848..5a35ec0033 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 3ea963abc0..1390337023 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 1c375110df..5ffb1848af 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index bbe545c50f..4371793223 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 2118f83d53..1d28e9c60f 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index bc60b754b6..596add3735 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 07f1e56543..842a7ef598 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index c4de322b1a..fb8ffc8d46 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index d0d98fb9f1..a9d1b60c09 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index f9715f2de6..b09f8a7752 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index b719e60727..c70126d8e0 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 470279e44b..d6fe48735a 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/delta/biv2.5/Configuration.h b/Marlin/example_configurations/delta/biv2.5/Configuration.h index 3033651173..a078b82a4c 100644 --- a/Marlin/example_configurations/delta/biv2.5/Configuration.h +++ b/Marlin/example_configurations/delta/biv2.5/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/delta/biv2.5/Configuration_adv.h b/Marlin/example_configurations/delta/biv2.5/Configuration_adv.h index 9183be44b3..f203817fb0 100644 --- a/Marlin/example_configurations/delta/biv2.5/Configuration_adv.h +++ b/Marlin/example_configurations/delta/biv2.5/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 9d7a500fdb..583f18cdfd 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index eb79a30413..447fe136a2 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 1091e9303d..266c202a05 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 7ec5948d02..447fe136a2 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index fde86a529a..f223c8f8bd 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index 811477921d..908d04885e 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 0cfd4e4658..699740cdcb 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 2a7399bb03..a501e1273e 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index d1ef7d39b2..f568733026 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 22cefd5388..ec97b4a409 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 7a307cc8e1..efa64e7625 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -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 + #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 + #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 diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 2ececd4c3a..841ff0c268 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -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 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 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 + */ +//#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +//#define EXTENDED_CAPABILITIES_REPORT #endif // CONFIGURATION_ADV_H diff --git a/Marlin/fastio.h b/Marlin/fastio.h index 3a608e0058..fff057a1c7 100644 --- a/Marlin/fastio.h +++ b/Marlin/fastio.h @@ -79,7 +79,7 @@ #define _GET_OUTPUT(IO) ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) != 0) /// check if pin is an timer -#define _GET_TIMER(IO) ((DIO ## IO ## _PWM) +#define _GET_TIMER(IO) (DIO ## IO ## _PWM) // why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html @@ -93,6 +93,8 @@ /// set pin as input wrapper #define SET_INPUT(IO) _SET_INPUT(IO) +/// set pin as input with pullup wrapper +#define SET_INPUT_PULLUP(IO) do{ _SET_INPUT(IO); _WRITE(IO, HIGH); }while(0) /// set pin as output wrapper #define SET_OUTPUT(IO) _SET_OUTPUT(IO) @@ -275,8 +277,6 @@ #define DIO21_DDR DDRC #define DIO21_PWM NULL - - #undef PB0 #define PB0_PIN PINB0 #define PB0_RPORT PINB @@ -1835,18 +1835,6 @@ #define PG5_WPORT PORTG #define PG5_DDR DDRG #define PG5_PWM &OCR0B - #undef PG6 - #define PG6_PIN PING6 - #define PG6_RPORT PING - #define PG6_WPORT PORTG - #define PG6_DDR DDRG - #define PG6_PWM NULL - #undef PG7 - #define PG7_PIN PING7 - #define PG7_RPORT PING - #define PG7_WPORT PORTG - #define PG7_DDR DDRG - #define PG7_PWM NULL #undef PH0 #define PH0_PIN PINH0 @@ -2064,343 +2052,342 @@ #define MOSI DIO10 // 22 #define SS DIO8 // 20 - #define DIO0_PIN PINA0 - #define DIO0_RPORT PINA - #define DIO0_WPORT PORTA - #define DIO0_PWM NULL - #define DIO0_DDR DDRA + #define DIO0_PIN PINA0 + #define DIO0_RPORT PINA + #define DIO0_WPORT PORTA + #define DIO0_PWM NULL + #define DIO0_DDR DDRA - #define DIO1_PIN PINA1 - #define DIO1_RPORT PINA - #define DIO1_WPORT PORTA - #define DIO1_PWM NULL - #define DIO1_DDR DDRA + #define DIO1_PIN PINA1 + #define DIO1_RPORT PINA + #define DIO1_WPORT PORTA + #define DIO1_PWM NULL + #define DIO1_DDR DDRA - #define DIO2_PIN PINA2 - #define DIO2_RPORT PINA - #define DIO2_WPORT PORTA - #define DIO2_PWM NULL - #define DIO2_DDR DDRA + #define DIO2_PIN PINA2 + #define DIO2_RPORT PINA + #define DIO2_WPORT PORTA + #define DIO2_PWM NULL + #define DIO2_DDR DDRA - #define DIO3_PIN PINA3 - #define DIO3_RPORT PINA - #define DIO3_WPORT PORTA - #define DIO3_PWM NULL - #define DIO3_DDR DDRA + #define DIO3_PIN PINA3 + #define DIO3_RPORT PINA + #define DIO3_WPORT PORTA + #define DIO3_PWM NULL + #define DIO3_DDR DDRA - #define DIO4_PIN PINA4 - #define DIO4_RPORT PINA - #define DIO4_WPORT PORTA - #define DIO4_PWM NULL - #define DIO4_DDR DDRA + #define DIO4_PIN PINA4 + #define DIO4_RPORT PINA + #define DIO4_WPORT PORTA + #define DIO4_PWM NULL + #define DIO4_DDR DDRA - #define DIO5_PIN PINA5 - #define DIO5_RPORT PINA - #define DIO5_WPORT PORTA - #define DIO5_PWM NULL - #define DIO5_DDR DDRA + #define DIO5_PIN PINA5 + #define DIO5_RPORT PINA + #define DIO5_WPORT PORTA + #define DIO5_PWM NULL + #define DIO5_DDR DDRA - #define DIO6_PIN PINA6 - #define DIO6_RPORT PINA - #define DIO6_WPORT PORTA - #define DIO6_PWM NULL - #define DIO6_DDR DDRA + #define DIO6_PIN PINA6 + #define DIO6_RPORT PINA + #define DIO6_WPORT PORTA + #define DIO6_PWM NULL + #define DIO6_DDR DDRA - #define DIO7_PIN PINA7 - #define DIO7_RPORT PINA - #define DIO7_WPORT PORTA - #define DIO7_PWM NULL - #define DIO7_DDR DDRA + #define DIO7_PIN PINA7 + #define DIO7_RPORT PINA + #define DIO7_WPORT PORTA + #define DIO7_PWM NULL + #define DIO7_DDR DDRA - #define DIO8_PIN PINB0 - #define DIO8_RPORT PINB - #define DIO8_WPORT PORTB - #define DIO8_PWM NULL - #define DIO8_DDR DDRB + #define DIO8_PIN PINB0 + #define DIO8_RPORT PINB + #define DIO8_WPORT PORTB + #define DIO8_PWM NULL + #define DIO8_DDR DDRB - #define DIO9_PIN PINB1 - #define DIO9_RPORT PINB - #define DIO9_WPORT PORTB - #define DIO9_PWM NULL - #define DIO9_DDR DDRB + #define DIO9_PIN PINB1 + #define DIO9_RPORT PINB + #define DIO9_WPORT PORTB + #define DIO9_PWM NULL + #define DIO9_DDR DDRB - #define DIO10_PIN PINB2 - #define DIO10_RPORT PINB - #define DIO10_WPORT PORTB - #define DIO10_PWM NULL - #define DIO10_DDR DDRB + #define DIO10_PIN PINB2 + #define DIO10_RPORT PINB + #define DIO10_WPORT PORTB + #define DIO10_PWM NULL + #define DIO10_DDR DDRB - #define DIO11_PIN PINB3 - #define DIO11_RPORT PINB - #define DIO11_WPORT PORTB - #define DIO11_PWM NULL - #define DIO11_DDR DDRB + #define DIO11_PIN PINB3 + #define DIO11_RPORT PINB + #define DIO11_WPORT PORTB + #define DIO11_PWM NULL + #define DIO11_DDR DDRB - #define DIO12_PIN PINB4 - #define DIO12_RPORT PINB - #define DIO12_WPORT PORTB - #define DIO12_PWM NULL - #define DIO12_DDR DDRB + #define DIO12_PIN PINB4 + #define DIO12_RPORT PINB + #define DIO12_WPORT PORTB + #define DIO12_PWM NULL + #define DIO12_DDR DDRB - #define DIO13_PIN PINB5 - #define DIO13_RPORT PINB - #define DIO13_WPORT PORTB - #define DIO13_PWM NULL - #define DIO13_DDR DDRB + #define DIO13_PIN PINB5 + #define DIO13_RPORT PINB + #define DIO13_WPORT PORTB + #define DIO13_PWM NULL + #define DIO13_DDR DDRB - #define DIO14_PIN PINB6 - #define DIO14_RPORT PINB - #define DIO14_WPORT PORTB - #define DIO14_PWM NULL - #define DIO14_DDR DDRB + #define DIO14_PIN PINB6 + #define DIO14_RPORT PINB + #define DIO14_WPORT PORTB + #define DIO14_PWM NULL + #define DIO14_DDR DDRB - #define DIO15_PIN PINB7 - #define DIO15_RPORT PINB - #define DIO15_WPORT PORTB - #define DIO15_PWM NULL - #define DIO15_DDR DDRB + #define DIO15_PIN PINB7 + #define DIO15_RPORT PINB + #define DIO15_WPORT PORTB + #define DIO15_PWM NULL + #define DIO15_DDR DDRB - #define DIO16_PIN PINC0 - #define DIO16_RPORT PINC - #define DIO16_WPORT PORTC - #define DIO16_PWM NULL - #define DIO16_DDR DDRC + #define DIO16_PIN PINC0 + #define DIO16_RPORT PINC + #define DIO16_WPORT PORTC + #define DIO16_PWM NULL + #define DIO16_DDR DDRC - #define DIO17_PIN PINC1 - #define DIO17_RPORT PINC - #define DIO17_WPORT PORTC - #define DIO17_PWM NULL - #define DIO17_DDR DDRC + #define DIO17_PIN PINC1 + #define DIO17_RPORT PINC + #define DIO17_WPORT PORTC + #define DIO17_PWM NULL + #define DIO17_DDR DDRC - #define DIO18_PIN PINC2 - #define DIO18_RPORT PINC - #define DIO18_WPORT PORTC - #define DIO18_PWM NULL - #define DIO18_DDR DDRC + #define DIO18_PIN PINC2 + #define DIO18_RPORT PINC + #define DIO18_WPORT PORTC + #define DIO18_PWM NULL + #define DIO18_DDR DDRC - #define DIO19_PIN PINC3 - #define DIO19_RPORT PINC - #define DIO19_WPORT PORTC - #define DIO19_PWM NULL - #define DIO19_DDR DDRC + #define DIO19_PIN PINC3 + #define DIO19_RPORT PINC + #define DIO19_WPORT PORTC + #define DIO19_PWM NULL + #define DIO19_DDR DDRC - #define DIO20_PIN PINC4 - #define DIO20_RPORT PINC - #define DIO20_WPORT PORTC - #define DIO20_PWM NULL - #define DIO20_DDR DDRC + #define DIO20_PIN PINC4 + #define DIO20_RPORT PINC + #define DIO20_WPORT PORTC + #define DIO20_PWM NULL + #define DIO20_DDR DDRC - #define DIO21_PIN PINC5 - #define DIO21_RPORT PINC - #define DIO21_WPORT PORTC - #define DIO21_PWM NULL - #define DIO21_DDR DDRC + #define DIO21_PIN PINC5 + #define DIO21_RPORT PINC + #define DIO21_WPORT PORTC + #define DIO21_PWM NULL + #define DIO21_DDR DDRC - #define DIO22_PIN PINC6 - #define DIO22_RPORT PINC - #define DIO22_WPORT PORTC - #define DIO22_PWM NULL - #define DIO22_DDR DDRC + #define DIO22_PIN PINC6 + #define DIO22_RPORT PINC + #define DIO22_WPORT PORTC + #define DIO22_PWM NULL + #define DIO22_DDR DDRC - #define DIO23_PIN PINC7 - #define DIO23_RPORT PINC - #define DIO23_WPORT PORTC - #define DIO23_PWM NULL - #define DIO23_DDR DDRC + #define DIO23_PIN PINC7 + #define DIO23_RPORT PINC + #define DIO23_WPORT PORTC + #define DIO23_PWM NULL + #define DIO23_DDR DDRC - #define DIO24_PIN PIND0 - #define DIO24_RPORT PIND - #define DIO24_WPORT PORTD - #define DIO24_PWM NULL - #define DIO24_DDR DDRD + #define DIO24_PIN PIND0 + #define DIO24_RPORT PIND + #define DIO24_WPORT PORTD + #define DIO24_PWM NULL + #define DIO24_DDR DDRD - #define DIO25_PIN PIND1 - #define DIO25_RPORT PIND - #define DIO25_WPORT PORTD - #define DIO25_PWM NULL - #define DIO25_DDR DDRD + #define DIO25_PIN PIND1 + #define DIO25_RPORT PIND + #define DIO25_WPORT PORTD + #define DIO25_PWM NULL + #define DIO25_DDR DDRD - #define DIO26_PIN PIND2 - #define DIO26_RPORT PIND - #define DIO26_WPORT PORTD - #define DIO26_PWM NULL - #define DIO26_DDR DDRD + #define DIO26_PIN PIND2 + #define DIO26_RPORT PIND + #define DIO26_WPORT PORTD + #define DIO26_PWM NULL + #define DIO26_DDR DDRD - #define DIO27_PIN PIND3 - #define DIO27_RPORT PIND - #define DIO27_WPORT PORTD - #define DIO27_PWM NULL - #define DIO27_DDR DDRD + #define DIO27_PIN PIND3 + #define DIO27_RPORT PIND + #define DIO27_WPORT PORTD + #define DIO27_PWM NULL + #define DIO27_DDR DDRD - #define DIO28_PIN PIND4 - #define DIO28_RPORT PIND - #define DIO28_WPORT PORTD - #define DIO28_PWM NULL - #define DIO28_DDR DDRD + #define DIO28_PIN PIND4 + #define DIO28_RPORT PIND + #define DIO28_WPORT PORTD + #define DIO28_PWM NULL + #define DIO28_DDR DDRD - #define DIO29_PIN PIND5 - #define DIO29_RPORT PIND - #define DIO29_WPORT PORTD - #define DIO29_PWM NULL - #define DIO29_DDR DDRD + #define DIO29_PIN PIND5 + #define DIO29_RPORT PIND + #define DIO29_WPORT PORTD + #define DIO29_PWM NULL + #define DIO29_DDR DDRD - #define DIO30_PIN PIND6 - #define DIO30_RPORT PIND - #define DIO30_WPORT PORTD - #define DIO30_PWM NULL - #define DIO30_DDR DDRD + #define DIO30_PIN PIND6 + #define DIO30_RPORT PIND + #define DIO30_WPORT PORTD + #define DIO30_PWM NULL + #define DIO30_DDR DDRD - #define DIO31_PIN PIND7 - #define DIO31_RPORT PIND - #define DIO31_WPORT PORTD - #define DIO31_PWM NULL - #define DIO31_DDR DDRD + #define DIO31_PIN PIND7 + #define DIO31_RPORT PIND + #define DIO31_WPORT PORTD + #define DIO31_PWM NULL + #define DIO31_DDR DDRD - #define DIO32_PIN PINE0 - #define DIO32_RPORT PINE - #define DIO32_WPORT PORTE - #define DIO32_PWM NULL - #define DIO32_DDR DDRE + #define DIO32_PIN PINE0 + #define DIO32_RPORT PINE + #define DIO32_WPORT PORTE + #define DIO32_PWM NULL + #define DIO32_DDR DDRE - #define DIO33_PIN PINE1 - #define DIO33_RPORT PINE - #define DIO33_WPORT PORTE - #define DIO33_PWM NULL - #define DIO33_DDR DDRE + #define DIO33_PIN PINE1 + #define DIO33_RPORT PINE + #define DIO33_WPORT PORTE + #define DIO33_PWM NULL + #define DIO33_DDR DDRE - #define DIO34_PIN PINE2 - #define DIO34_RPORT PINE - #define DIO34_WPORT PORTE - #define DIO34_PWM NULL - #define DIO34_DDR DDRE + #define DIO34_PIN PINE2 + #define DIO34_RPORT PINE + #define DIO34_WPORT PORTE + #define DIO34_PWM NULL + #define DIO34_DDR DDRE - #define DIO35_PIN PINE3 - #define DIO35_RPORT PINE - #define DIO35_WPORT PORTE - #define DIO35_PWM NULL - #define DIO35_DDR DDRE + #define DIO35_PIN PINE3 + #define DIO35_RPORT PINE + #define DIO35_WPORT PORTE + #define DIO35_PWM NULL + #define DIO35_DDR DDRE - #define DIO36_PIN PINE4 - #define DIO36_RPORT PINE - #define DIO36_WPORT PORTE - #define DIO36_PWM NULL - #define DIO36_DDR DDRE + #define DIO36_PIN PINE4 + #define DIO36_RPORT PINE + #define DIO36_WPORT PORTE + #define DIO36_PWM NULL + #define DIO36_DDR DDRE - #define DIO37_PIN PINE5 - #define DIO37_RPORT PINE - #define DIO37_WPORT PORTE - #define DIO37_PWM NULL - #define DIO37_DDR DDRE + #define DIO37_PIN PINE5 + #define DIO37_RPORT PINE + #define DIO37_WPORT PORTE + #define DIO37_PWM NULL + #define DIO37_DDR DDRE - #define DIO38_PIN PINE6 - #define DIO38_RPORT PINE - #define DIO38_WPORT PORTE - #define DIO38_PWM NULL - #define DIO38_DDR DDRE + #define DIO38_PIN PINE6 + #define DIO38_RPORT PINE + #define DIO38_WPORT PORTE + #define DIO38_PWM NULL + #define DIO38_DDR DDRE - #define DIO39_PIN PINE7 - #define DIO39_RPORT PINE - #define DIO39_WPORT PORTE - #define DIO39_PWM NULL - #define DIO39_DDR DDRE + #define DIO39_PIN PINE7 + #define DIO39_RPORT PINE + #define DIO39_WPORT PORTE + #define DIO39_PWM NULL + #define DIO39_DDR DDRE - #define AIO0_PIN PINF0 - #define AIO0_RPORT PINF - #define AIO0_WPORT PORTF - #define AIO0_PWM NULL - #define AIO0_DDR DDRF + #define AIO0_PIN PINF0 + #define AIO0_RPORT PINF + #define AIO0_WPORT PORTF + #define AIO0_PWM NULL + #define AIO0_DDR DDRF - #define AIO1_PIN PINF1 - #define AIO1_RPORT PINF - #define AIO1_WPORT PORTF - #define AIO1_PWM NULL - #define AIO1_DDR DDRF + #define AIO1_PIN PINF1 + #define AIO1_RPORT PINF + #define AIO1_WPORT PORTF + #define AIO1_PWM NULL + #define AIO1_DDR DDRF - #define AIO2_PIN PINF2 - #define AIO2_RPORT PINF - #define AIO2_WPORT PORTF - #define AIO2_PWM NULL - #define AIO2_DDR DDRF + #define AIO2_PIN PINF2 + #define AIO2_RPORT PINF + #define AIO2_WPORT PORTF + #define AIO2_PWM NULL + #define AIO2_DDR DDRF - #define AIO3_PIN PINF3 - #define AIO3_RPORT PINF - #define AIO3_WPORT PORTF - #define AIO3_PWM NULL - #define AIO3_DDR DDRF + #define AIO3_PIN PINF3 + #define AIO3_RPORT PINF + #define AIO3_WPORT PORTF + #define AIO3_PWM NULL + #define AIO3_DDR DDRF - #define AIO4_PIN PINF4 - #define AIO4_RPORT PINF - #define AIO4_WPORT PORTF - #define AIO4_PWM NULL - #define AIO4_DDR DDRF + #define AIO4_PIN PINF4 + #define AIO4_RPORT PINF + #define AIO4_WPORT PORTF + #define AIO4_PWM NULL + #define AIO4_DDR DDRF - #define AIO5_PIN PINF5 - #define AIO5_RPORT PINF - #define AIO5_WPORT PORTF - #define AIO5_PWM NULL - #define AIO5_DDR DDRF + #define AIO5_PIN PINF5 + #define AIO5_RPORT PINF + #define AIO5_WPORT PORTF + #define AIO5_PWM NULL + #define AIO5_DDR DDRF - #define AIO6_PIN PINF6 - #define AIO6_RPORT PINF - #define AIO6_WPORT PORTF - #define AIO6_PWM NULL - #define AIO6_DDR DDRF + #define AIO6_PIN PINF6 + #define AIO6_RPORT PINF + #define AIO6_WPORT PORTF + #define AIO6_PWM NULL + #define AIO6_DDR DDRF - #define AIO7_PIN PINF7 - #define AIO7_RPORT PINF - #define AIO7_WPORT PORTF - #define AIO7_PWM NULL - #define AIO7_DDR DDRF + #define AIO7_PIN PINF7 + #define AIO7_RPORT PINF + #define AIO7_WPORT PORTF + #define AIO7_PWM NULL + #define AIO7_DDR DDRF - #define DIO40_PIN PINF0 - #define DIO40_RPORT PINF - #define DIO40_WPORT PORTF - #define DIO40_PWM NULL - #define DIO40_DDR DDRF + #define DIO40_PIN PINF0 + #define DIO40_RPORT PINF + #define DIO40_WPORT PORTF + #define DIO40_PWM NULL + #define DIO40_DDR DDRF - #define DIO41_PIN PINF1 - #define DIO41_RPORT PINF - #define DIO41_WPORT PORTF - #define DIO41_PWM NULL - #define DIO41_DDR DDRF + #define DIO41_PIN PINF1 + #define DIO41_RPORT PINF + #define DIO41_WPORT PORTF + #define DIO41_PWM NULL + #define DIO41_DDR DDRF - #define DIO42_PIN PINF2 - #define DIO42_RPORT PINF - #define DIO42_WPORT PORTF - #define DIO42_PWM NULL - #define DIO42_DDR DDRF + #define DIO42_PIN PINF2 + #define DIO42_RPORT PINF + #define DIO42_WPORT PORTF + #define DIO42_PWM NULL + #define DIO42_DDR DDRF - #define DIO43_PIN PINF3 - #define DIO43_RPORT PINF - #define DIO43_WPORT PORTF - #define DIO43_PWM NULL - #define DIO43_DDR DDRF + #define DIO43_PIN PINF3 + #define DIO43_RPORT PINF + #define DIO43_WPORT PORTF + #define DIO43_PWM NULL + #define DIO43_DDR DDRF - #define DIO44_PIN PINF4 - #define DIO44_RPORT PINF - #define DIO44_WPORT PORTF - #define DIO44_PWM NULL - #define DIO44_DDR DDRF + #define DIO44_PIN PINF4 + #define DIO44_RPORT PINF + #define DIO44_WPORT PORTF + #define DIO44_PWM NULL + #define DIO44_DDR DDRF - #define DIO45_PIN PINF5 - #define DIO45_RPORT PINF - #define DIO45_WPORT PORTF - #define DIO45_PWM NULL - #define DIO45_DDR DDRF + #define DIO45_PIN PINF5 + #define DIO45_RPORT PINF + #define DIO45_WPORT PORTF + #define DIO45_PWM NULL + #define DIO45_DDR DDRF - #define DIO46_PIN PINF6 - #define DIO46_RPORT PINF - #define DIO46_WPORT PORTF - #define DIO46_PWM NULL - #define DIO46_DDR DDRF - - #define DIO47_PIN PINF7 - #define DIO47_RPORT PINF - #define DIO47_WPORT PORTF - #define DIO47_PWM NULL - #define DIO47_DDR DDRF + #define DIO46_PIN PINF6 + #define DIO46_RPORT PINF + #define DIO46_WPORT PORTF + #define DIO46_PWM NULL + #define DIO46_DDR DDRF + #define DIO47_PIN PINF7 + #define DIO47_RPORT PINF + #define DIO47_WPORT PORTF + #define DIO47_PWM NULL + #define DIO47_DDR DDRF #undef PA0 @@ -2709,643 +2696,643 @@ */ // SPI - #define SCK DIO21 // 9 - #define MISO DIO23 // 11 - #define MOSI DIO22 // 10 - #define SS DIO20 // 8 + #define SCK DIO21 // 9 + #define MISO DIO23 // 11 + #define MOSI DIO22 // 10 + #define SS DIO20 // 8 - #define DIO0_PIN PIND0 - #define DIO0_RPORT PIND - #define DIO0_WPORT PORTD - #define DIO0_PWM NULL - #define DIO0_DDR DDRD + #define DIO0_PIN PIND0 + #define DIO0_RPORT PIND + #define DIO0_WPORT PORTD + #define DIO0_PWM NULL + #define DIO0_DDR DDRD - #define DIO1_PIN PIND1 - #define DIO1_RPORT PIND - #define DIO1_WPORT PORTD - #define DIO1_PWM NULL - #define DIO1_DDR DDRD + #define DIO1_PIN PIND1 + #define DIO1_RPORT PIND + #define DIO1_WPORT PORTD + #define DIO1_PWM NULL + #define DIO1_DDR DDRD - #define DIO2_PIN PIND2 - #define DIO2_RPORT PIND - #define DIO2_WPORT PORTD - #define DIO2_PWM NULL - #define DIO2_DDR DDRD + #define DIO2_PIN PIND2 + #define DIO2_RPORT PIND + #define DIO2_WPORT PORTD + #define DIO2_PWM NULL + #define DIO2_DDR DDRD - #define DIO3_PIN PIND3 - #define DIO3_RPORT PIND - #define DIO3_WPORT PORTD - #define DIO3_PWM NULL - #define DIO3_DDR DDRD + #define DIO3_PIN PIND3 + #define DIO3_RPORT PIND + #define DIO3_WPORT PORTD + #define DIO3_PWM NULL + #define DIO3_DDR DDRD - #define DIO4_PIN PIND4 - #define DIO4_RPORT PIND - #define DIO4_WPORT PORTD - #define DIO4_PWM NULL - #define DIO4_DDR DDRD + #define DIO4_PIN PIND4 + #define DIO4_RPORT PIND + #define DIO4_WPORT PORTD + #define DIO4_PWM NULL + #define DIO4_DDR DDRD - #define DIO5_PIN PIND5 - #define DIO5_RPORT PIND - #define DIO5_WPORT PORTD - #define DIO5_PWM NULL - #define DIO5_DDR DDRD + #define DIO5_PIN PIND5 + #define DIO5_RPORT PIND + #define DIO5_WPORT PORTD + #define DIO5_PWM NULL + #define DIO5_DDR DDRD - #define DIO6_PIN PIND6 - #define DIO6_RPORT PIND - #define DIO6_WPORT PORTD - #define DIO6_PWM NULL - #define DIO6_DDR DDRD + #define DIO6_PIN PIND6 + #define DIO6_RPORT PIND + #define DIO6_WPORT PORTD + #define DIO6_PWM NULL + #define DIO6_DDR DDRD - #define DIO7_PIN PIND7 - #define DIO7_RPORT PIND - #define DIO7_WPORT PORTD - #define DIO7_PWM NULL - #define DIO7_DDR DDRD + #define DIO7_PIN PIND7 + #define DIO7_RPORT PIND + #define DIO7_WPORT PORTD + #define DIO7_PWM NULL + #define DIO7_DDR DDRD - #define DIO8_PIN PINE0 - #define DIO8_RPORT PINE - #define DIO8_WPORT PORTE - #define DIO8_PWM NULL - #define DIO8_DDR DDRE + #define DIO8_PIN PINE0 + #define DIO8_RPORT PINE + #define DIO8_WPORT PORTE + #define DIO8_PWM NULL + #define DIO8_DDR DDRE - #define DIO9_PIN PINE1 - #define DIO9_RPORT PINE - #define DIO9_WPORT PORTE - #define DIO9_PWM NULL - #define DIO9_DDR DDRE + #define DIO9_PIN PINE1 + #define DIO9_RPORT PINE + #define DIO9_WPORT PORTE + #define DIO9_PWM NULL + #define DIO9_DDR DDRE - #define DIO10_PIN PINC0 + #define DIO10_PIN PINC0 #define DIO10_RPORT PINC #define DIO10_WPORT PORTC - #define DIO10_PWM NULL - #define DIO10_DDR DDRC + #define DIO10_PWM NULL + #define DIO10_DDR DDRC - #define DIO11_PIN PINC1 + #define DIO11_PIN PINC1 #define DIO11_RPORT PINC #define DIO11_WPORT PORTC - #define DIO11_PWM NULL - #define DIO11_DDR DDRC + #define DIO11_PWM NULL + #define DIO11_DDR DDRC - #define DIO12_PIN PINC2 + #define DIO12_PIN PINC2 #define DIO12_RPORT PINC #define DIO12_WPORT PORTC - #define DIO12_PWM NULL - #define DIO12_DDR DDRC + #define DIO12_PWM NULL + #define DIO12_DDR DDRC - #define DIO13_PIN PINC3 + #define DIO13_PIN PINC3 #define DIO13_RPORT PINC #define DIO13_WPORT PORTC - #define DIO13_PWM NULL - #define DIO13_DDR DDRC + #define DIO13_PWM NULL + #define DIO13_DDR DDRC - #define DIO14_PIN PINC4 + #define DIO14_PIN PINC4 #define DIO14_RPORT PINC #define DIO14_WPORT PORTC - #define DIO14_PWM NULL - #define DIO14_DDR DDRC + #define DIO14_PWM NULL + #define DIO14_DDR DDRC - #define DIO15_PIN PINC5 + #define DIO15_PIN PINC5 #define DIO15_RPORT PINC #define DIO15_WPORT PORTC - #define DIO15_PWM NULL - #define DIO15_DDR DDRC + #define DIO15_PWM NULL + #define DIO15_DDR DDRC - #define DIO16_PIN PINC6 + #define DIO16_PIN PINC6 #define DIO16_RPORT PINC #define DIO16_WPORT PORTC - #define DIO16_PWM NULL - #define DIO16_DDR DDRC + #define DIO16_PWM NULL + #define DIO16_DDR DDRC - #define DIO17_PIN PINC7 + #define DIO17_PIN PINC7 #define DIO17_RPORT PINC #define DIO17_WPORT PORTC - #define DIO17_PWM NULL - #define DIO17_DDR DDRC + #define DIO17_PWM NULL + #define DIO17_DDR DDRC - #define DIO18_PIN PINE6 + #define DIO18_PIN PINE6 #define DIO18_RPORT PINE #define DIO18_WPORT PORTE - #define DIO18_PWM NULL - #define DIO18_DDR DDRE + #define DIO18_PWM NULL + #define DIO18_DDR DDRE - #define DIO19_PIN PINE7 + #define DIO19_PIN PINE7 #define DIO19_RPORT PINE #define DIO19_WPORT PORTE - #define DIO19_PWM NULL - #define DIO19_DDR DDRE + #define DIO19_PWM NULL + #define DIO19_DDR DDRE - #define DIO20_PIN PINB0 + #define DIO20_PIN PINB0 #define DIO20_RPORT PINB #define DIO20_WPORT PORTB - #define DIO20_PWM NULL - #define DIO20_DDR DDRB + #define DIO20_PWM NULL + #define DIO20_DDR DDRB - #define DIO21_PIN PINB1 + #define DIO21_PIN PINB1 #define DIO21_RPORT PINB #define DIO21_WPORT PORTB - #define DIO21_PWM NULL - #define DIO21_DDR DDRB + #define DIO21_PWM NULL + #define DIO21_DDR DDRB - #define DIO22_PIN PINB2 + #define DIO22_PIN PINB2 #define DIO22_RPORT PINB #define DIO22_WPORT PORTB - #define DIO22_PWM NULL - #define DIO22_DDR DDRB + #define DIO22_PWM NULL + #define DIO22_DDR DDRB - #define DIO23_PIN PINB3 + #define DIO23_PIN PINB3 #define DIO23_RPORT PINB #define DIO23_WPORT PORTB - #define DIO23_PWM NULL - #define DIO23_DDR DDRB + #define DIO23_PWM NULL + #define DIO23_DDR DDRB - #define DIO24_PIN PINB4 + #define DIO24_PIN PINB4 #define DIO24_RPORT PINB #define DIO24_WPORT PORTB - #define DIO24_PWM NULL - #define DIO24_DDR DDRB + #define DIO24_PWM NULL + #define DIO24_DDR DDRB - #define DIO25_PIN PINB5 + #define DIO25_PIN PINB5 #define DIO25_RPORT PINB #define DIO25_WPORT PORTB - #define DIO25_PWM NULL - #define DIO25_DDR DDRB + #define DIO25_PWM NULL + #define DIO25_DDR DDRB - #define DIO26_PIN PINB6 + #define DIO26_PIN PINB6 #define DIO26_RPORT PINB #define DIO26_WPORT PORTB - #define DIO26_PWM NULL - #define DIO26_DDR DDRB + #define DIO26_PWM NULL + #define DIO26_DDR DDRB - #define DIO27_PIN PINB7 + #define DIO27_PIN PINB7 #define DIO27_RPORT PINB #define DIO27_WPORT PORTB - #define DIO27_PWM NULL - #define DIO27_DDR DDRB + #define DIO27_PWM NULL + #define DIO27_DDR DDRB - #define DIO28_PIN PINA0 + #define DIO28_PIN PINA0 #define DIO28_RPORT PINA #define DIO28_WPORT PORTA - #define DIO28_PWM NULL - #define DIO28_DDR DDRA + #define DIO28_PWM NULL + #define DIO28_DDR DDRA - #define DIO29_PIN PINA1 + #define DIO29_PIN PINA1 #define DIO29_RPORT PINA #define DIO29_WPORT PORTA - #define DIO29_PWM NULL - #define DIO29_DDR DDRA + #define DIO29_PWM NULL + #define DIO29_DDR DDRA - #define DIO30_PIN PINA2 + #define DIO30_PIN PINA2 #define DIO30_RPORT PINA #define DIO30_WPORT PORTA - #define DIO30_PWM NULL - #define DIO30_DDR DDRA + #define DIO30_PWM NULL + #define DIO30_DDR DDRA - #define DIO31_PIN PINA3 + #define DIO31_PIN PINA3 #define DIO31_RPORT PINA #define DIO31_WPORT PORTA - #define DIO31_PWM NULL - #define DIO31_DDR DDRA + #define DIO31_PWM NULL + #define DIO31_DDR DDRA - #define DIO32_PIN PINA4 + #define DIO32_PIN PINA4 #define DIO32_RPORT PINA #define DIO32_WPORT PORTA - #define DIO32_PWM NULL - #define DIO32_DDR DDRA + #define DIO32_PWM NULL + #define DIO32_DDR DDRA - #define DIO33_PIN PINA5 + #define DIO33_PIN PINA5 #define DIO33_RPORT PINA #define DIO33_WPORT PORTA - #define DIO33_PWM NULL - #define DIO33_DDR DDRA + #define DIO33_PWM NULL + #define DIO33_DDR DDRA - #define DIO34_PIN PINA6 + #define DIO34_PIN PINA6 #define DIO34_RPORT PINA #define DIO34_WPORT PORTA - #define DIO34_PWM NULL - #define DIO34_DDR DDRA + #define DIO34_PWM NULL + #define DIO34_DDR DDRA - #define DIO35_PIN PINA7 + #define DIO35_PIN PINA7 #define DIO35_RPORT PINA #define DIO35_WPORT PORTA - #define DIO35_PWM NULL - #define DIO35_DDR DDRA + #define DIO35_PWM NULL + #define DIO35_DDR DDRA - #define DIO36_PIN PINE4 + #define DIO36_PIN PINE4 #define DIO36_RPORT PINE #define DIO36_WPORT PORTE - #define DIO36_PWM NULL - #define DIO36_DDR DDRE + #define DIO36_PWM NULL + #define DIO36_DDR DDRE - #define DIO37_PIN PINE5 + #define DIO37_PIN PINE5 #define DIO37_RPORT PINE #define DIO37_WPORT PORTE - #define DIO37_PWM NULL - #define DIO37_DDR DDRE + #define DIO37_PWM NULL + #define DIO37_DDR DDRE - #define DIO38_PIN PINF0 + #define DIO38_PIN PINF0 #define DIO38_RPORT PINF #define DIO38_WPORT PORTF - #define DIO38_PWM NULL - #define DIO38_DDR DDRF + #define DIO38_PWM NULL + #define DIO38_DDR DDRF - #define DIO39_PIN PINF1 + #define DIO39_PIN PINF1 #define DIO39_RPORT PINF #define DIO39_WPORT PORTF - #define DIO39_PWM NULL - #define DIO39_DDR DDRF + #define DIO39_PWM NULL + #define DIO39_DDR DDRF - #define DIO40_PIN PINF2 + #define DIO40_PIN PINF2 #define DIO40_RPORT PINF #define DIO40_WPORT PORTF - #define DIO40_PWM NULL - #define DIO40_DDR DDRF + #define DIO40_PWM NULL + #define DIO40_DDR DDRF - #define DIO41_PIN PINF3 + #define DIO41_PIN PINF3 #define DIO41_RPORT PINF #define DIO41_WPORT PORTF - #define DIO41_PWM NULL - #define DIO41_DDR DDRF + #define DIO41_PWM NULL + #define DIO41_DDR DDRF - #define DIO42_PIN PINF4 + #define DIO42_PIN PINF4 #define DIO42_RPORT PINF #define DIO42_WPORT PORTF - #define DIO42_PWM NULL - #define DIO42_DDR DDRF + #define DIO42_PWM NULL + #define DIO42_DDR DDRF - #define DIO43_PIN PINF5 + #define DIO43_PIN PINF5 #define DIO43_RPORT PINF #define DIO43_WPORT PORTF - #define DIO43_PWM NULL - #define DIO43_DDR DDRF + #define DIO43_PWM NULL + #define DIO43_DDR DDRF - #define DIO44_PIN PINF6 + #define DIO44_PIN PINF6 #define DIO44_RPORT PINF #define DIO44_WPORT PORTF - #define DIO44_PWM NULL - #define DIO44_DDR DDRF + #define DIO44_PWM NULL + #define DIO44_DDR DDRF - #define DIO45_PIN PINF7 + #define DIO45_PIN PINF7 #define DIO45_RPORT PINF #define DIO45_WPORT PORTF - #define DIO45_PWM NULL - #define DIO45_DDR DDRF + #define DIO45_PWM NULL + #define DIO45_DDR DDRF - #define AIO0_PIN PINF0 - #define AIO0_RPORT PINF - #define AIO0_WPORT PORTF - #define AIO0_PWM NULL - #define AIO0_DDR DDRF + #define AIO0_PIN PINF0 + #define AIO0_RPORT PINF + #define AIO0_WPORT PORTF + #define AIO0_PWM NULL + #define AIO0_DDR DDRF - #define AIO1_PIN PINF1 - #define AIO1_RPORT PINF - #define AIO1_WPORT PORTF - #define AIO1_PWM NULL - #define AIO1_DDR DDRF + #define AIO1_PIN PINF1 + #define AIO1_RPORT PINF + #define AIO1_WPORT PORTF + #define AIO1_PWM NULL + #define AIO1_DDR DDRF - #define AIO2_PIN PINF2 - #define AIO2_RPORT PINF - #define AIO2_WPORT PORTF - #define AIO2_PWM NULL - #define AIO2_DDR DDRF + #define AIO2_PIN PINF2 + #define AIO2_RPORT PINF + #define AIO2_WPORT PORTF + #define AIO2_PWM NULL + #define AIO2_DDR DDRF - #define AIO3_PIN PINF3 - #define AIO3_RPORT PINF - #define AIO3_WPORT PORTF - #define AIO3_PWM NULL - #define AIO3_DDR DDRF + #define AIO3_PIN PINF3 + #define AIO3_RPORT PINF + #define AIO3_WPORT PORTF + #define AIO3_PWM NULL + #define AIO3_DDR DDRF - #define AIO4_PIN PINF4 - #define AIO4_RPORT PINF - #define AIO4_WPORT PORTF - #define AIO4_PWM NULL - #define AIO4_DDR DDRF + #define AIO4_PIN PINF4 + #define AIO4_RPORT PINF + #define AIO4_WPORT PORTF + #define AIO4_PWM NULL + #define AIO4_DDR DDRF - #define AIO5_PIN PINF5 - #define AIO5_RPORT PINF - #define AIO5_WPORT PORTF - #define AIO5_PWM NULL - #define AIO5_DDR DDRF + #define AIO5_PIN PINF5 + #define AIO5_RPORT PINF + #define AIO5_WPORT PORTF + #define AIO5_PWM NULL + #define AIO5_DDR DDRF - #define AIO6_PIN PINF6 - #define AIO6_RPORT PINF - #define AIO6_WPORT PORTF - #define AIO6_PWM NULL - #define AIO6_DDR DDRF + #define AIO6_PIN PINF6 + #define AIO6_RPORT PINF + #define AIO6_WPORT PORTF + #define AIO6_PWM NULL + #define AIO6_DDR DDRF - #define AIO7_PIN PINF7 - #define AIO7_RPORT PINF - #define AIO7_WPORT PORTF - #define AIO7_PWM NULL - #define AIO7_DDR DDRF + #define AIO7_PIN PINF7 + #define AIO7_RPORT PINF + #define AIO7_WPORT PORTF + #define AIO7_PWM NULL + #define AIO7_DDR DDRF //-- Begin not supported by Teensyduino //-- don't use Arduino functions on these pins pinMode/digitalWrite/etc - #define DIO46_PIN PINE2 + #define DIO46_PIN PINE2 #define DIO46_RPORT PINE #define DIO46_WPORT PORTE - #define DIO46_PWM NULL - #define DIO46_DDR DDRE + #define DIO46_PWM NULL + #define DIO46_DDR DDRE - #define DIO47_PIN PINE3 + #define DIO47_PIN PINE3 #define DIO47_RPORT PINE #define DIO47_WPORT PORTE - #define DIO47_PWM NULL - #define DIO47_DDR DDRE + #define DIO47_PWM NULL + #define DIO47_DDR DDRE //-- end not supported by Teensyduino #undef PA0 - #define PA0_PIN PINA0 - #define PA0_RPORT PINA - #define PA0_WPORT PORTA - #define PA0_PWM NULL - #define PA0_DDR DDRA + #define PA0_PIN PINA0 + #define PA0_RPORT PINA + #define PA0_WPORT PORTA + #define PA0_PWM NULL + #define PA0_DDR DDRA #undef PA1 - #define PA1_PIN PINA1 - #define PA1_RPORT PINA - #define PA1_WPORT PORTA - #define PA1_PWM NULL - #define PA1_DDR DDRA + #define PA1_PIN PINA1 + #define PA1_RPORT PINA + #define PA1_WPORT PORTA + #define PA1_PWM NULL + #define PA1_DDR DDRA #undef PA2 - #define PA2_PIN PINA2 - #define PA2_RPORT PINA - #define PA2_WPORT PORTA - #define PA2_PWM NULL - #define PA2_DDR DDRA + #define PA2_PIN PINA2 + #define PA2_RPORT PINA + #define PA2_WPORT PORTA + #define PA2_PWM NULL + #define PA2_DDR DDRA #undef PA3 - #define PA3_PIN PINA3 - #define PA3_RPORT PINA - #define PA3_WPORT PORTA - #define PA3_PWM NULL - #define PA3_DDR DDRA + #define PA3_PIN PINA3 + #define PA3_RPORT PINA + #define PA3_WPORT PORTA + #define PA3_PWM NULL + #define PA3_DDR DDRA #undef PA4 - #define PA4_PIN PINA4 - #define PA4_RPORT PINA - #define PA4_WPORT PORTA - #define PA4_PWM NULL - #define PA4_DDR DDRA + #define PA4_PIN PINA4 + #define PA4_RPORT PINA + #define PA4_WPORT PORTA + #define PA4_PWM NULL + #define PA4_DDR DDRA #undef PA5 - #define PA5_PIN PINA5 - #define PA5_RPORT PINA - #define PA5_WPORT PORTA - #define PA5_PWM NULL - #define PA5_DDR DDRA + #define PA5_PIN PINA5 + #define PA5_RPORT PINA + #define PA5_WPORT PORTA + #define PA5_PWM NULL + #define PA5_DDR DDRA #undef PA6 - #define PA6_PIN PINA6 - #define PA6_RPORT PINA - #define PA6_WPORT PORTA - #define PA6_PWM NULL - #define PA6_DDR DDRA + #define PA6_PIN PINA6 + #define PA6_RPORT PINA + #define PA6_WPORT PORTA + #define PA6_PWM NULL + #define PA6_DDR DDRA #undef PA7 - #define PA7_PIN PINA7 - #define PA7_RPORT PINA - #define PA7_WPORT PORTA - #define PA7_PWM NULL - #define PA7_DDR DDRA + #define PA7_PIN PINA7 + #define PA7_RPORT PINA + #define PA7_WPORT PORTA + #define PA7_PWM NULL + #define PA7_DDR DDRA #undef PB0 - #define PB0_PIN PINB0 - #define PB0_RPORT PINB - #define PB0_WPORT PORTB - #define PB0_PWM NULL - #define PB0_DDR DDRB + #define PB0_PIN PINB0 + #define PB0_RPORT PINB + #define PB0_WPORT PORTB + #define PB0_PWM NULL + #define PB0_DDR DDRB #undef PB1 - #define PB1_PIN PINB1 - #define PB1_RPORT PINB - #define PB1_WPORT PORTB - #define PB1_PWM NULL - #define PB1_DDR DDRB + #define PB1_PIN PINB1 + #define PB1_RPORT PINB + #define PB1_WPORT PORTB + #define PB1_PWM NULL + #define PB1_DDR DDRB #undef PB2 - #define PB2_PIN PINB2 - #define PB2_RPORT PINB - #define PB2_WPORT PORTB - #define PB2_PWM NULL - #define PB2_DDR DDRB + #define PB2_PIN PINB2 + #define PB2_RPORT PINB + #define PB2_WPORT PORTB + #define PB2_PWM NULL + #define PB2_DDR DDRB #undef PB3 - #define PB3_PIN PINB3 - #define PB3_RPORT PINB - #define PB3_WPORT PORTB - #define PB3_PWM NULL - #define PB3_DDR DDRB + #define PB3_PIN PINB3 + #define PB3_RPORT PINB + #define PB3_WPORT PORTB + #define PB3_PWM NULL + #define PB3_DDR DDRB #undef PB4 - #define PB4_PIN PINB4 - #define PB4_RPORT PINB - #define PB4_WPORT PORTB - #define PB4_PWM NULL - #define PB4_DDR DDRB + #define PB4_PIN PINB4 + #define PB4_RPORT PINB + #define PB4_WPORT PORTB + #define PB4_PWM NULL + #define PB4_DDR DDRB #undef PB5 - #define PB5_PIN PINB5 - #define PB5_RPORT PINB - #define PB5_WPORT PORTB - #define PB5_PWM NULL - #define PB5_DDR DDRB + #define PB5_PIN PINB5 + #define PB5_RPORT PINB + #define PB5_WPORT PORTB + #define PB5_PWM NULL + #define PB5_DDR DDRB #undef PB6 - #define PB6_PIN PINB6 - #define PB6_RPORT PINB - #define PB6_WPORT PORTB - #define PB6_PWM NULL - #define PB6_DDR DDRB + #define PB6_PIN PINB6 + #define PB6_RPORT PINB + #define PB6_WPORT PORTB + #define PB6_PWM NULL + #define PB6_DDR DDRB #undef PB7 - #define PB7_PIN PINB7 - #define PB7_RPORT PINB - #define PB7_WPORT PORTB - #define PB7_PWM NULL - #define PB7_DDR DDRB + #define PB7_PIN PINB7 + #define PB7_RPORT PINB + #define PB7_WPORT PORTB + #define PB7_PWM NULL + #define PB7_DDR DDRB #undef PC0 - #define PC0_PIN PINC0 - #define PC0_RPORT PINC - #define PC0_WPORT PORTC - #define PC0_PWM NULL - #define PC0_DDR DDRC + #define PC0_PIN PINC0 + #define PC0_RPORT PINC + #define PC0_WPORT PORTC + #define PC0_PWM NULL + #define PC0_DDR DDRC #undef PC1 - #define PC1_PIN PINC1 - #define PC1_RPORT PINC - #define PC1_WPORT PORTC - #define PC1_PWM NULL - #define PC1_DDR DDRC + #define PC1_PIN PINC1 + #define PC1_RPORT PINC + #define PC1_WPORT PORTC + #define PC1_PWM NULL + #define PC1_DDR DDRC #undef PC2 - #define PC2_PIN PINC2 - #define PC2_RPORT PINC - #define PC2_WPORT PORTC - #define PC2_PWM NULL - #define PC2_DDR DDRC + #define PC2_PIN PINC2 + #define PC2_RPORT PINC + #define PC2_WPORT PORTC + #define PC2_PWM NULL + #define PC2_DDR DDRC #undef PC3 - #define PC3_PIN PINC3 - #define PC3_RPORT PINC - #define PC3_WPORT PORTC - #define PC3_PWM NULL - #define PC3_DDR DDRC + #define PC3_PIN PINC3 + #define PC3_RPORT PINC + #define PC3_WPORT PORTC + #define PC3_PWM NULL + #define PC3_DDR DDRC #undef PC4 - #define PC4_PIN PINC4 - #define PC4_RPORT PINC - #define PC4_WPORT PORTC - #define PC4_PWM NULL - #define PC4_DDR DDRC + #define PC4_PIN PINC4 + #define PC4_RPORT PINC + #define PC4_WPORT PORTC + #define PC4_PWM NULL + #define PC4_DDR DDRC #undef PC5 - #define PC5_PIN PINC5 - #define PC5_RPORT PINC - #define PC5_WPORT PORTC - #define PC5_PWM NULL - #define PC5_DDR DDRC + #define PC5_PIN PINC5 + #define PC5_RPORT PINC + #define PC5_WPORT PORTC + #define PC5_PWM NULL + #define PC5_DDR DDRC #undef PC6 - #define PC6_PIN PINC6 - #define PC6_RPORT PINC - #define PC6_WPORT PORTC - #define PC6_PWM NULL - #define PC6_DDR DDRC + #define PC6_PIN PINC6 + #define PC6_RPORT PINC + #define PC6_WPORT PORTC + #define PC6_PWM NULL + #define PC6_DDR DDRC #undef PC7 - #define PC7_PIN PINC7 - #define PC7_RPORT PINC - #define PC7_WPORT PORTC - #define PC7_PWM NULL - #define PC7_DDR DDRC + #define PC7_PIN PINC7 + #define PC7_RPORT PINC + #define PC7_WPORT PORTC + #define PC7_PWM NULL + #define PC7_DDR DDRC #undef PD0 - #define PD0_PIN PIND0 - #define PD0_RPORT PIND - #define PD0_WPORT PORTD - #define PD0_PWM NULL - #define PD0_DDR DDRD + #define PD0_PIN PIND0 + #define PD0_RPORT PIND + #define PD0_WPORT PORTD + #define PD0_PWM NULL + #define PD0_DDR DDRD #undef PD1 - #define PD1_PIN PIND1 - #define PD1_RPORT PIND - #define PD1_WPORT PORTD - #define PD1_PWM NULL - #define PD1_DDR DDRD + #define PD1_PIN PIND1 + #define PD1_RPORT PIND + #define PD1_WPORT PORTD + #define PD1_PWM NULL + #define PD1_DDR DDRD #undef PD2 - #define PD2_PIN PIND2 - #define PD2_RPORT PIND - #define PD2_WPORT PORTD - #define PD2_PWM NULL - #define PD2_DDR DDRD + #define PD2_PIN PIND2 + #define PD2_RPORT PIND + #define PD2_WPORT PORTD + #define PD2_PWM NULL + #define PD2_DDR DDRD #undef PD3 - #define PD3_PIN PIND3 - #define PD3_RPORT PIND - #define PD3_WPORT PORTD - #define PD3_PWM NULL - #define PD3_DDR DDRD + #define PD3_PIN PIND3 + #define PD3_RPORT PIND + #define PD3_WPORT PORTD + #define PD3_PWM NULL + #define PD3_DDR DDRD #undef PD4 - #define PD4_PIN PIND4 - #define PD4_RPORT PIND - #define PD4_WPORT PORTD - #define PD4_PWM NULL - #define PD4_DDR DDRD + #define PD4_PIN PIND4 + #define PD4_RPORT PIND + #define PD4_WPORT PORTD + #define PD4_PWM NULL + #define PD4_DDR DDRD #undef PD5 - #define PD5_PIN PIND5 - #define PD5_RPORT PIND - #define PD5_WPORT PORTD - #define PD5_PWM NULL - #define PD5_DDR DDRD + #define PD5_PIN PIND5 + #define PD5_RPORT PIND + #define PD5_WPORT PORTD + #define PD5_PWM NULL + #define PD5_DDR DDRD #undef PD6 - #define PD6_PIN PIND6 - #define PD6_RPORT PIND - #define PD6_WPORT PORTD - #define PD6_PWM NULL - #define PD6_DDR DDRD + #define PD6_PIN PIND6 + #define PD6_RPORT PIND + #define PD6_WPORT PORTD + #define PD6_PWM NULL + #define PD6_DDR DDRD #undef PD7 - #define PD7_PIN PIND7 - #define PD7_RPORT PIND - #define PD7_WPORT PORTD - #define PD7_PWM NULL - #define PD7_DDR DDRD + #define PD7_PIN PIND7 + #define PD7_RPORT PIND + #define PD7_WPORT PORTD + #define PD7_PWM NULL + #define PD7_DDR DDRD #undef PE0 - #define PE0_PIN PINE0 - #define PE0_RPORT PINE - #define PE0_WPORT PORTE - #define PE0_PWM NULL - #define PE0_DDR DDRE + #define PE0_PIN PINE0 + #define PE0_RPORT PINE + #define PE0_WPORT PORTE + #define PE0_PWM NULL + #define PE0_DDR DDRE #undef PE1 - #define PE1_PIN PINE1 - #define PE1_RPORT PINE - #define PE1_WPORT PORTE - #define PE1_PWM NULL - #define PE1_DDR DDRE + #define PE1_PIN PINE1 + #define PE1_RPORT PINE + #define PE1_WPORT PORTE + #define PE1_PWM NULL + #define PE1_DDR DDRE #undef PE2 - #define PE2_PIN PINE2 - #define PE2_RPORT PINE - #define PE2_WPORT PORTE - #define PE2_PWM NULL - #define PE2_DDR DDRE + #define PE2_PIN PINE2 + #define PE2_RPORT PINE + #define PE2_WPORT PORTE + #define PE2_PWM NULL + #define PE2_DDR DDRE #undef PE3 - #define PE3_PIN PINE3 - #define PE3_RPORT PINE - #define PE3_WPORT PORTE - #define PE3_PWM NULL - #define PE3_DDR DDRE + #define PE3_PIN PINE3 + #define PE3_RPORT PINE + #define PE3_WPORT PORTE + #define PE3_PWM NULL + #define PE3_DDR DDRE #undef PE4 - #define PE4_PIN PINE4 - #define PE4_RPORT PINE - #define PE4_WPORT PORTE - #define PE4_PWM NULL - #define PE4_DDR DDRE + #define PE4_PIN PINE4 + #define PE4_RPORT PINE + #define PE4_WPORT PORTE + #define PE4_PWM NULL + #define PE4_DDR DDRE #undef PE5 - #define PE5_PIN PINE5 - #define PE5_RPORT PINE - #define PE5_WPORT PORTE - #define PE5_PWM NULL - #define PE5_DDR DDRE + #define PE5_PIN PINE5 + #define PE5_RPORT PINE + #define PE5_WPORT PORTE + #define PE5_PWM NULL + #define PE5_DDR DDRE #undef PE6 - #define PE6_PIN PINE6 - #define PE6_RPORT PINE - #define PE6_WPORT PORTE - #define PE6_PWM NULL - #define PE6_DDR DDRE + #define PE6_PIN PINE6 + #define PE6_RPORT PINE + #define PE6_WPORT PORTE + #define PE6_PWM NULL + #define PE6_DDR DDRE #undef PE7 - #define PE7_PIN PINE7 - #define PE7_RPORT PINE - #define PE7_WPORT PORTE - #define PE7_PWM NULL - #define PE7_DDR DDRE + #define PE7_PIN PINE7 + #define PE7_RPORT PINE + #define PE7_WPORT PORTE + #define PE7_PWM NULL + #define PE7_DDR DDRE #undef PF0 - #define PF0_PIN PINF0 - #define PF0_RPORT PINF - #define PF0_WPORT PORTF - #define PF0_PWM NULL - #define PF0_DDR DDRF + #define PF0_PIN PINF0 + #define PF0_RPORT PINF + #define PF0_WPORT PORTF + #define PF0_PWM NULL + #define PF0_DDR DDRF #undef PF1 - #define PF1_PIN PINF1 - #define PF1_RPORT PINF - #define PF1_WPORT PORTF - #define PF1_PWM NULL - #define PF1_DDR DDRF + #define PF1_PIN PINF1 + #define PF1_RPORT PINF + #define PF1_WPORT PORTF + #define PF1_PWM NULL + #define PF1_DDR DDRF #undef PF2 - #define PF2_PIN PINF2 - #define PF2_RPORT PINF - #define PF2_WPORT PORTF - #define PF2_PWM NULL - #define PF2_DDR DDRF + #define PF2_PIN PINF2 + #define PF2_RPORT PINF + #define PF2_WPORT PORTF + #define PF2_PWM NULL + #define PF2_DDR DDRF #undef PF3 - #define PF3_PIN PINF3 - #define PF3_RPORT PINF - #define PF3_WPORT PORTF - #define PF3_PWM NULL - #define PF3_DDR DDRF + #define PF3_PIN PINF3 + #define PF3_RPORT PINF + #define PF3_WPORT PORTF + #define PF3_PWM NULL + #define PF3_DDR DDRF #undef PF4 - #define PF4_PIN PINF4 - #define PF4_RPORT PINF - #define PF4_WPORT PORTF - #define PF4_PWM NULL - #define PF4_DDR DDRF + #define PF4_PIN PINF4 + #define PF4_RPORT PINF + #define PF4_WPORT PORTF + #define PF4_PWM NULL + #define PF4_DDR DDRF #undef PF5 - #define PF5_PIN PINF5 - #define PF5_RPORT PINF - #define PF5_WPORT PORTF - #define PF5_PWM NULL - #define PF5_DDR DDRF + #define PF5_PIN PINF5 + #define PF5_RPORT PINF + #define PF5_WPORT PORTF + #define PF5_PWM NULL + #define PF5_DDR DDRF #undef PF6 - #define PF6_PIN PINF6 - #define PF6_RPORT PINF - #define PF6_WPORT PORTF - #define PF6_PWM NULL - #define PF6_DDR DDRF + #define PF6_PIN PINF6 + #define PF6_RPORT PINF + #define PF6_WPORT PORTF + #define PF6_PWM NULL + #define PF6_DDR DDRF #undef PF7 - #define PF7_PIN PINF7 - #define PF7_RPORT PINF - #define PF7_WPORT PORTF - #define PF7_PWM NULL - #define PF7_DDR DDRF + #define PF7_PIN PINF7 + #define PF7_RPORT PINF + #define PF7_WPORT PORTF + #define PF7_PWM NULL + #define PF7_DDR DDRF #endif // AT90USBxx_TEENSYPP_ASSIGNMENTS Teensyduino assignments #endif // __AVR_AT90usbxxx__ diff --git a/Marlin/language.h b/Marlin/language.h index 496fed5c96..d25cf138a4 100644 --- a/Marlin/language.h +++ b/Marlin/language.h @@ -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 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 diff --git a/Marlin/language_an.h b/Marlin/language_an.h index bfabc0a57e..8d6ccd9448 100644 --- a/Marlin/language_an.h +++ b/Marlin/language_an.h @@ -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" diff --git a/Marlin/language_bg.h b/Marlin/language_bg.h index 51606947c5..520b935f95 100644 --- a/Marlin/language_bg.h +++ b/Marlin/language_bg.h @@ -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 diff --git a/Marlin/language_ca.h b/Marlin/language_ca.h index b90f1c3951..8bb97060a3 100644 --- a/Marlin/language_ca.h +++ b/Marlin/language_ca.h @@ -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 " diff --git a/Marlin/language_cn.h b/Marlin/language_cn.h index 86c639dfac..a34c17c23d 100644 --- a/Marlin/language_cn.h +++ b/Marlin/language_cn.h @@ -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 " diff --git a/Marlin/language_cz.h b/Marlin/language_cz.h index 742cd8c1be..ed17581dac 100644 --- a/Marlin/language_cz.h +++ b/Marlin/language_cz.h @@ -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?" diff --git a/Marlin/language_da.h b/Marlin/language_da.h index b107ca05dc..e1eb1680c7 100644 --- a/Marlin/language_da.h +++ b/Marlin/language_da.h @@ -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 diff --git a/Marlin/language_de.h b/Marlin/language_de.h index 9744378fcd..551374b8fd 100644 --- a/Marlin/language_de.h +++ b/Marlin/language_de.h @@ -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 diff --git a/Marlin/language_el-gr.h b/Marlin/language_el-gr.h index 510e8aae3c..db0798f0d3 100644 --- a/Marlin/language_el-gr.h +++ b/Marlin/language_el-gr.h @@ -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 "Φόρτωση" diff --git a/Marlin/language_el.h b/Marlin/language_el.h index 9d1c8555ac..21cee03104 100644 --- a/Marlin/language_el.h +++ b/Marlin/language_el.h @@ -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 " diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 6cf7d52c5b..0529d98690 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -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 diff --git a/Marlin/language_es.h b/Marlin/language_es.h index 2943fcf962..ca992203c9 100644 --- a/Marlin/language_es.h +++ b/Marlin/language_es.h @@ -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 diff --git a/Marlin/language_eu.h b/Marlin/language_eu.h index 909d6c85d4..0d663597f3 100644 --- a/Marlin/language_eu.h +++ b/Marlin/language_eu.h @@ -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 " diff --git a/Marlin/language_fi.h b/Marlin/language_fi.h index b73a207e27..e7db9a2d9b 100644 --- a/Marlin/language_fi.h +++ b/Marlin/language_fi.h @@ -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 " diff --git a/Marlin/language_fr.h b/Marlin/language_fr.h index 52adbcba0c..c567b6804e 100644 --- a/Marlin/language_fr.h +++ b/Marlin/language_fr.h @@ -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 diff --git a/Marlin/language_gl.h b/Marlin/language_gl.h index c5fbbc9fa7..1ece3594d7 100644 --- a/Marlin/language_gl.h +++ b/Marlin/language_gl.h @@ -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 diff --git a/Marlin/language_hr.h b/Marlin/language_hr.h index 603521506d..3bf88de10f 100644 --- a/Marlin/language_hr.h +++ b/Marlin/language_hr.h @@ -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 diff --git a/Marlin/language_it.h b/Marlin/language_it.h index 047272bc6f..76b4a60710 100644 --- a/Marlin/language_it.h +++ b/Marlin/language_it.h @@ -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" diff --git a/Marlin/language_kana.h b/Marlin/language_kana.h index 67136e2987..76e28a86f4 100644 --- a/Marlin/language_kana.h +++ b/Marlin/language_kana.h @@ -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") diff --git a/Marlin/language_kana_utf8.h b/Marlin/language_kana_utf8.h index 3e46f57d82..f23c7c2aaa 100644 --- a/Marlin/language_kana_utf8.h +++ b/Marlin/language_kana_utf8.h @@ -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" diff --git a/Marlin/language_nl.h b/Marlin/language_nl.h index 5f682bd90e..f21ece8305 100644 --- a/Marlin/language_nl.h +++ b/Marlin/language_nl.h @@ -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 " diff --git a/Marlin/language_pl.h b/Marlin/language_pl.h index b1559c4a46..39cef81f94 100644 --- a/Marlin/language_pl.h +++ b/Marlin/language_pl.h @@ -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 diff --git a/Marlin/language_pt-br.h b/Marlin/language_pt-br.h index 3db6e15c70..fe5b834fd6 100644 --- a/Marlin/language_pt-br.h +++ b/Marlin/language_pt-br.h @@ -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 " diff --git a/Marlin/language_pt-br_utf8.h b/Marlin/language_pt-br_utf8.h index a556c24303..7fb4117403 100644 --- a/Marlin/language_pt-br_utf8.h +++ b/Marlin/language_pt-br_utf8.h @@ -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 " diff --git a/Marlin/language_pt.h b/Marlin/language_pt.h index a0df879fc8..d73af9ea56 100644 --- a/Marlin/language_pt.h +++ b/Marlin/language_pt.h @@ -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 " diff --git a/Marlin/language_pt_utf8.h b/Marlin/language_pt_utf8.h index 24ce828b5b..536896b1d6 100644 --- a/Marlin/language_pt_utf8.h +++ b/Marlin/language_pt_utf8.h @@ -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 " diff --git a/Marlin/language_ru.h b/Marlin/language_ru.h index aa381c88fe..7441f34caa 100644 --- a/Marlin/language_ru.h +++ b/Marlin/language_ru.h @@ -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 "Aмакс" #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 diff --git a/Marlin/language_test.h b/Marlin/language_test.h index 99fa712a71..25b9c09474 100644 --- a/Marlin/language_test.h +++ b/Marlin/language_test.h @@ -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 diff --git a/Marlin/language_tr.h b/Marlin/language_tr.h new file mode 100644 index 0000000000..1bd3f32a0a --- /dev/null +++ b/Marlin/language_tr.h @@ -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 . + * + */ + +/** + * 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 diff --git a/Marlin/language_tr_utf8.h b/Marlin/language_tr_utf8.h new file mode 100644 index 0000000000..922d54c3d2 --- /dev/null +++ b/Marlin/language_tr_utf8.h @@ -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 . + * + */ + +/** + * Turkish + * + * LCD Menu Messages + * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + */ +#ifndef LANGUAGE_TR_UTF_H +#define LANGUAGE_TR_UTF_H + +//#define SIMULATE_ROMFONT +#define DISPLAY_CHARSET_ISO10646_TR + +#define WELCOME_MSG MACHINE_NAME " hazır." //hazır. +#define MSG_SD_INSERTED "SD Yerleşti." //SD Yerleşti. +#define MSG_SD_REMOVED "SD Çıkarıldı." //SD Çıkarıldı. +#define MSG_LCD_ENDSTOPS "Endstops" // Max length 8 characters //Endstops +#define MSG_MAIN "Ana" //Ana +#define MSG_AUTOSTART "Otobaşlat" //Otobaşlat +#define MSG_DISABLE_STEPPERS "Motorları Durdur" //Motorları Durdur +#define MSG_AUTO_HOME "Eksenleri Sıfırla" //Eksenleri Sıfırla +#define MSG_AUTO_HOME_X "X Sıfırla" //X Sıfırla +#define MSG_AUTO_HOME_Y "Y Sıfırla" //Y Sıfırla +#define MSG_AUTO_HOME_Z "Z Sıfırla" //Z Sıfırla +#define MSG_LEVEL_BED_HOMING "XYZ Sıfırlanıyor" //XYZ Sıfırlanıyor +#define MSG_LEVEL_BED_WAITING "Başlatmak için tıkla" //Başlatmak için tıkla +#define MSG_LEVEL_BED_NEXT_POINT "Sıradaki Nokta" //Sıradaki Nokta +#define MSG_LEVEL_BED_DONE "Seviyeleme Tamam!" //Seviyeleme Tamam! +#define MSG_LEVEL_BED_CANCEL "İptal" //İptal +#define MSG_SET_HOME_OFFSETS "Offset Ayarla" //Offset Ayarla +#define MSG_HOME_OFFSETS_APPLIED "Offset Tamam" //Offset Tamam +#define MSG_SET_ORIGIN "Sıfır Belirle" //Sıfır Belirle +#define MSG_PREHEAT_1 "Ön Isınma PLA" //Ön Isınma PLA +#define MSG_PREHEAT_1_N MSG_PREHEAT_1 " " // +#define MSG_PREHEAT_1_ALL MSG_PREHEAT_1 " Tüm" // 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 "Ön Isınma ABS" //Ön Isınma ABS +#define MSG_PREHEAT_2_N MSG_PREHEAT_2 " " // +#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 " Tüm" // 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ğut" //Soğut +#define MSG_SWITCH_PS_ON "Gücü Aç" //Gücü Aç +#define MSG_SWITCH_PS_OFF "Gücü Kapat" //Gücü Kapat +#define MSG_EXTRUDE "Extrude" //Extrude +#define MSG_RETRACT "Geri Çek" //Geri Çek +#define MSG_MOVE_AXIS "Eksen Yönet" //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ız" //Hız +#define MSG_BED_Z "Tabla Z" //Tabla Z +#define MSG_NOZZLE "Nozül" //Nozül +#define MSG_BED "Tabla" //Tabla +#define MSG_FAN_SPEED "Fan Hızı" //Fan Hızı +#define MSG_FLOW "Akış" //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 " Çarpan" // Ç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ç" //Seç +#define MSG_ACC "İvme" //İ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ıcaklık" //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. Çap" //Fil. Çap +#define MSG_CONTRAST "LCD Kontrast" //LCD Kontrast +#define MSG_STORE_EPROM "Hafızaya Al" //Hafızaya Al +#define MSG_LOAD_EPROM "Hafızadan Yükle" //Hafızadan Yükle +#define MSG_RESTORE_FAILSAFE "Fabrika Ayarları" //Fabrika Ayarları +#define MSG_REFRESH "Yenile" //Yenile +#define MSG_WATCH "Bilgi Ekranı" //Bilgi Ekranı +#define MSG_PREPARE "Hazırlık" //Hazırlık +#define MSG_TUNE "Ayar" //Ayar +#define MSG_PAUSE_PRINT "Duraklat" //Duraklat +#define MSG_RESUME_PRINT "Sürdür" //Sürdür +#define MSG_STOP_PRINT "Durdur" //Durdur +#define MSG_CARD_MENU "SD den Yazdır" //SD den Yazdır +#define MSG_NO_CARD "SD Kart Yok" //SD Kart Yok +#define MSG_DWELL "Uyku..." //Uyku... +#define MSG_USERWAIT "Operatör bekleniyor..." //Operatör bekleniyor... +#define MSG_RESUMING "Baskı Sürdürülüyor" //Baskı Sürdürülüyor +#define MSG_PRINT_ABORTED "Baskı Durduruldu" //Baskı Durduruldu +#define MSG_NO_MOVE "İşlem yok." //İşlem yok. +#define MSG_KILLED "Kilitlendi. " //Kilitlendi. +#define MSG_STOPPED "Durdu. " //Durdu. +#define MSG_CONTROL_RETRACT "Geri Çek mm" //Geri Çek mm +#define MSG_CONTROL_RETRACT_SWAP "Swap Re.mm" //Swap Re.mm +#define MSG_CONTROL_RETRACTF "Geri Çekme 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ğiştir" //Filaman Değiştir +#define MSG_INIT_SDCARD "Init. SD" //Init. SD +#define MSG_CNG_SDCARD "SD Değiştir" //SD Değiştir +#define MSG_ZPROBE_OUT "Z Prob Açık. Tabla" //Z Prob Açık. Tabla +#define MSG_BLTOUCH_SELFTEST "BLTouch Self-Test" //BLTouch Self-Test +#define MSG_BLTOUCH_RESET "Sıfırla BLTouch" //Sıfırla BLTouch +#define MSG_HOME "Sıfırla" //Sıfırla +#define MSG_FIRST "önce" //Önce +#define MSG_ZPROBE_ZOFFSET "Z Offset" //Z Offset +#define MSG_BABYSTEP_X "Miniadım X" //Miniadım X +#define MSG_BABYSTEP_Y "Miniadım Y" //Miniadım Y +#define MSG_BABYSTEP_Z "Miniadım Z" //Miniadım Z +#define MSG_ENDSTOP_ABORT "Endstop iptal" //Endstop iptal +#define MSG_HEATING_FAILED_LCD "Isınma başarısız" //Isınma başarısız +#define MSG_ERR_REDUNDANT_TEMP "Hata: Geçersiz Sıcaklık" //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ılamaz" //G28 Z Yapılamaz +#define MSG_HALTED "YAZICI DURDURULDU" //YAZICI DURDURULDU +#define MSG_PLEASE_RESET "Lütfen 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ınıyor..." //Isınıyor... +#define MSG_HEATING_COMPLETE "Isınma tamam." //Isınma tamam. +#define MSG_BED_HEATING "Tabla Isınıyor." //Tabla Isınıyor. +#define MSG_BED_DONE "Tabla hazır." //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ıcı Hakkında" //Yazıcı Hakkında +#define MSG_INFO_PRINTER_MENU "Yazıcı Bilgisi" //Yazıcı Bilgisi +#define MSG_INFO_STATS_MENU "İstatistikler" //İstatistikler +#define MSG_INFO_BOARD_MENU "Kontrolör Bilgisi" //Kontrol Bilgisi +#define MSG_INFO_THERMISTOR_MENU "Termistörler" //Termistörler +#define MSG_INFO_EXTRUDERS "Ekstruderler" //Ekstruderler +#define MSG_INFO_BAUDRATE "İletişim Hızı" //İletişim Hızı +#define MSG_INFO_PROTOCOL "Protokol" //Protokol + +#if LCD_WIDTH > 19 + #define MSG_INFO_PRINT_COUNT "Baskı Sayısı" //Baskı Sayısı + #define MSG_INFO_COMPLETED_PRINTS "Tamamlanan" //Tamamlanan + #define MSG_INFO_PRINT_TIME "Toplam Baskı Süresi" //Toplam Baskı Süresi + #define MSG_INFO_PRINT_LONGEST "En Uzun Baskı Süresi" //En Uzun Baskı Süresi + #define MSG_INFO_PRINT_FILAMENT "Toplam Filaman" //Toplam Filaman +#else + #define MSG_INFO_PRINT_COUNT "Baskı" //Baskı + #define MSG_INFO_COMPLETED_PRINTS "Tamamlanan" //Tamamlanan + #define MSG_INFO_PRINT_TIME "Süre" //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ıc." //Min Sıcak. +#define MSG_INFO_MAX_TEMP "Max Sıc." //Max Sıcak. +#define MSG_INFO_PSU "Güç Kaynağı" //Güç Kaynağı + +#define MSG_DRIVE_STRENGTH "Sürücü Gücü" //Sürücü Gücü +#define MSG_DAC_PERCENT "Sürücü %" //Sürücü % +#define MSG_DAC_EEPROM_WRITE "DAC'ı EEPROM'a Yaz" //DAC'ı EEPROM'a Yaz +#define MSG_FILAMENT_CHANGE_HEADER "Filaman Değiştir" //Filaman Değiştir +#define MSG_FILAMENT_CHANGE_OPTION_HEADER "Seçenekler:" //Seçenekler: +#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "Daha Akıt" //Daha Akıt +#define MSG_FILAMENT_CHANGE_OPTION_RESUME "Baskıyı sürdür" //Baskıyı sürdür +#if LCD_HEIGHT >= 4 + #define MSG_FILAMENT_CHANGE_INIT_1 "Başlama bekleniyor" //Başlama bekleniyor + #define MSG_FILAMENT_CHANGE_INIT_2 "filamanın" //filamanın + #define MSG_FILAMENT_CHANGE_INIT_3 "değişimi" //değişimi + #define MSG_FILAMENT_CHANGE_UNLOAD_1 "Bekleniyor" //Bekleniyor + #define MSG_FILAMENT_CHANGE_UNLOAD_2 "filamanın çıkması" //filamanın çıkması + #define MSG_FILAMENT_CHANGE_UNLOAD_3 "" // + #define MSG_FILAMENT_CHANGE_INSERT_1 "Filamanı yükle" //Filamanı yükle + #define MSG_FILAMENT_CHANGE_INSERT_2 "ve devam için" //ve devam için + #define MSG_FILAMENT_CHANGE_INSERT_3 "tuşa bas..." //tuşa bas... + #define MSG_FILAMENT_CHANGE_LOAD_1 "Bekleniyor" //Bekleniyor + #define MSG_FILAMENT_CHANGE_LOAD_2 "filamanın yüklenmesi" //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ı" //filaman akması + #define MSG_FILAMENT_CHANGE_EXTRUDE_3 "" // + #define MSG_FILAMENT_CHANGE_RESUME_1 "Baskının sürdürülmesini" //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ütfen bekleyiniz..." //Lütfen bekleyiniz... + #define MSG_FILAMENT_CHANGE_UNLOAD_1 "Çıkartılıyor..." //Çıkartılıyor... + #define MSG_FILAMENT_CHANGE_INSERT_1 "Yükle ve bas" //Yükle ve bas + #define MSG_FILAMENT_CHANGE_LOAD_1 "Yüklüyor..." //Yüklüyor... + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Akıtılıyor..." //Akıtılıyor... + #define MSG_FILAMENT_CHANGE_RESUME_1 "Sürdürülüyor..." //Sürdürülüyor... +#endif // LCD_HEIGHT < 4 + +#endif // LANGUAGE_TR_UTF_H diff --git a/Marlin/language_uk.h b/Marlin/language_uk.h new file mode 100644 index 0000000000..0308ab74d4 --- /dev/null +++ b/Marlin/language_uk.h @@ -0,0 +1,233 @@ +/** + * 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 . + * + */ + +/** + * Ukrainian + * + * LCD Menu Messages + * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + */ +#ifndef LANGUAGE_UK_H +#define LANGUAGE_UK_H + +#define MAPPER_D0D1 // For Cyrillic +#define DISPLAY_CHARSET_ISO10646_5 + +#define WELCOME_MSG MACHINE_NAME " готовий." +#define MSG_SD_INSERTED "Картка вставлена" +#define MSG_SD_REMOVED "Картка видалена" +#define MSG_LCD_ENDSTOPS "Кінцевик" // Max length 8 characters +#define MSG_MAIN "Меню" +#define MSG_AUTOSTART "Автостарт" +#define MSG_DISABLE_STEPPERS "Вимк. двигуни" +#define MSG_AUTO_HOME "Авто паркування" +#define MSG_AUTO_HOME_X "Паркування X" +#define MSG_AUTO_HOME_Y "Паркування Y" +#define MSG_AUTO_HOME_Z "Паркування Z" +#define MSG_LEVEL_BED_HOMING "Паркування XYZ" +#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 "Зміщення застос." +#define MSG_SET_ORIGIN "Встанов. початок" +#define MSG_PREHEAT_1 "Нагрів PLA" +#define MSG_PREHEAT_1_N MSG_PREHEAT_1 " " +#define MSG_PREHEAT_1_ALL MSG_PREHEAT_1 " Все" +#define MSG_PREHEAT_1_BEDONLY MSG_PREHEAT_1 " Стіл" +#define MSG_PREHEAT_1_SETTINGS MSG_PREHEAT_1 " нал." +#define MSG_PREHEAT_2 "Нагрів ABS" +#define MSG_PREHEAT_2_N MSG_PREHEAT_2 " " +#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 " Все" +#define MSG_PREHEAT_2_BEDONLY MSG_PREHEAT_2 " Стіл" +#define MSG_PREHEAT_2_SETTINGS MSG_PREHEAT_2 " нал." +#define MSG_COOLDOWN "Охолодження" +#define MSG_SWITCH_PS_ON "Увімкнути живлення" +#define MSG_SWITCH_PS_OFF "Вимкнути живлення" +#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" +#define MSG_MOVE_E "Екструдер" +#define MSG_MOVE_01MM "Рух по 0.1mm" +#define MSG_MOVE_1MM "Рух по 1mm" +#define MSG_MOVE_10MM "Рух по 10mm" +#define MSG_SPEED "Швидкість" +#define MSG_BED_Z "Z Столу" +#define MSG_NOZZLE "Сопло" +#define MSG_BED "Стіл" +#define MSG_FAN_SPEED "Охолодж." +#define MSG_FLOW "Потік" +#define MSG_CONTROL "Налаштування" +#define MSG_MIN " " LCD_STR_THERMOMETER " Мін" +#define MSG_MAX " " LCD_STR_THERMOMETER " Макс" +#define MSG_FACTOR " " LCD_STR_THERMOMETER " Факт" +#define MSG_AUTOTEMP "Автотемпер." +#define MSG_ON "Увімк." +#define MSG_OFF "Вимк. " +#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_SELECT "Вибрати" +#define MSG_ACC "Приск." +#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 "Aмакс " +#define MSG_A_RETRACT "A-втягув." +#define MSG_A_TRAVEL "A-руху" +#define MSG_XSTEPS "Xкроків/мм" +#define MSG_YSTEPS "Yкроків/мм" +#define MSG_ZSTEPS "Zкроків/мм" +#define MSG_ESTEPS "Eкроків/мм" +#define MSG_TEMPERATURE "Температура" +#define MSG_MOTION "Рух" +#define MSG_VOLUMETRIC "Волокно" +#define MSG_VOLUMETRIC_ENABLED "E в мм3" +#define MSG_FILAMENT_DIAM "Діам. волок." +#define MSG_CONTRAST "контраст LCD" +#define MSG_STORE_EPROM "Зберегти в ПЗП" +#define MSG_LOAD_EPROM "Зчитати з ПЗП" +#define MSG_RESTORE_FAILSAFE "Відновити базові" +#define MSG_REFRESH "Поновити" +#define MSG_WATCH "Інформація" +#define MSG_PREPARE "Підготувати" +#define MSG_TUNE "Підлаштування" +#define MSG_PAUSE_PRINT "Призупинити друк" +#define MSG_RESUME_PRINT "Відновити друк" +#define MSG_STOP_PRINT "Скасувати друк" +#define MSG_CARD_MENU "Друкувати з SD" +#define MSG_NO_CARD "Відсутня SD карт." +#define MSG_DWELL "Сплячка..." +#define MSG_USERWAIT "Очікування дій..." +#define MSG_RESUMING "Відновлення друку" +#define MSG_PRINT_ABORTED "Друк скасовано" +#define MSG_NO_MOVE "Немає руху." +#define MSG_KILLED "ПЕРЕРВАНО. " +#define MSG_STOPPED "ЗУПИНЕНО. " +#define MSG_FILAMENTCHANGE "Зміна волокна" +#define MSG_INIT_SDCARD "Старт SD картки" +#define MSG_CNG_SDCARD "Заміна SD карти" +#define MSG_ZPROBE_OUT "Z дет. не в межах" +#define MSG_BLTOUCH_SELFTEST "BLTouch Само-Тест" +#define MSG_BLTOUCH_RESET "Скинути BLTouch" +#define MSG_HOME "Дім" // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST +#define MSG_FIRST "перший" +#define MSG_ZPROBE_ZOFFSET "Зміщення 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_THERMAL_RUNAWAY "ЗБІЙ ТЕМПЕРАТУРИ" +#define MSG_ERR_Z_HOMING "G28 Z Відмовлено" +#define MSG_HALTED "ПРИНТЕР ЗУПИНЕНО" +#define MSG_PLEASE_RESET "Перезавантажте" +#define MSG_SHORT_DAY "д" // One character only +#define MSG_SHORT_HOUR "г" // One character only +#define MSG_SHORT_MINUTE "х" // One character only +#define MSG_HEATING "Нагрівання..." +#define MSG_HEATING_COMPLETE "Нагріто." +#define MSG_BED_HEATING "Нагрівання столу." +#define MSG_BED_DONE "Стіл нагрітий." +#define MSG_DELTA_CALIBRATE "Калібр. Delta" +#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 "Про принтер" +#define MSG_INFO_PRINTER_MENU "Інформація" +#define MSG_INFO_STATS_MENU "Статистика" +#define MSG_INFO_BOARD_MENU "Про плату" +#define MSG_INFO_THERMISTOR_MENU "Термістори" +#define MSG_INFO_EXTRUDERS "Екструдери" +#define MSG_INFO_BAUDRATE "біт/с" +#define MSG_INFO_PROTOCOL "Протокол" +#define MSG_LIGHTS_ON "Підсвітка увік." +#define MSG_LIGHTS_OFF "Підсвітка вимк." + +#if LCD_WIDTH >= 20 + #define MSG_INFO_PRINT_COUNT "К-сть друків" + #define MSG_INFO_COMPLETED_PRINTS "Завершено" + #define MSG_INFO_PRINT_TIME "Весь час друку" + #define MSG_INFO_PRINT_LONGEST "Найдовший час" + #define MSG_INFO_PRINT_FILAMENT "Екструдовано" +#else + #define MSG_INFO_PRINT_COUNT "Друків" + #define MSG_INFO_COMPLETED_PRINTS "Завершено" + #define MSG_INFO_PRINT_TIME "Загалом" + #define MSG_INFO_PRINT_LONGEST "Найдовший" + #define MSG_INFO_PRINT_FILAMENT "Ексдруд." +#endif + +#define MSG_INFO_MIN_TEMP "Мін Темп." +#define MSG_INFO_MAX_TEMP "Макс Темп." +#define MSG_INFO_PSU "Джерело жив." + +#define MSG_DRIVE_STRENGTH "Сила мотору" +#define MSG_DAC_PERCENT "% мотору" +#define MSG_DAC_EEPROM_WRITE "Запис ЦАП на ПЗП" +#define MSG_FILAMENT_CHANGE_HEADER "ЗАМІНА ВОЛОКНА" +#define MSG_FILAMENT_CHANGE_OPTION_HEADER "НАЛАШТ. ЗАМІНИ:" +#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE "Екструдувати" +#define MSG_FILAMENT_CHANGE_OPTION_RESUME "Відновити друк" + +#if LCD_HEIGHT >= 4 + #define MSG_FILAMENT_CHANGE_INIT_1 "Зачекайте на" + #define MSG_FILAMENT_CHANGE_INIT_2 "початок заміни" + #define MSG_FILAMENT_CHANGE_INIT_3 "волокна" + #define MSG_FILAMENT_CHANGE_UNLOAD_1 "Зачекайте на" + #define MSG_FILAMENT_CHANGE_UNLOAD_2 "вивід волокна" + #define MSG_FILAMENT_CHANGE_UNLOAD_3 "" + #define MSG_FILAMENT_CHANGE_INSERT_1 "Вставте волокно" + #define MSG_FILAMENT_CHANGE_INSERT_2 "та натисніть для" + #define MSG_FILAMENT_CHANGE_INSERT_3 "продовження..." + #define MSG_FILAMENT_CHANGE_LOAD_1 "Зачекайте на" + #define MSG_FILAMENT_CHANGE_LOAD_2 "ввід волокна" + #define MSG_FILAMENT_CHANGE_LOAD_3 "" + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Зачекайте на" + #define MSG_FILAMENT_CHANGE_EXTRUDE_2 "екструзію" + #define MSG_FILAMENT_CHANGE_EXTRUDE_3 "волокна" + #define MSG_FILAMENT_CHANGE_RESUME_1 "Зачекайте на" + #define MSG_FILAMENT_CHANGE_RESUME_2 "відновлення" + #define MSG_FILAMENT_CHANGE_RESUME_3 "друку" +#else // LCD_HEIGHT < 4 + #define MSG_FILAMENT_CHANGE_INIT_1 "Зачекайте..." + #define MSG_FILAMENT_CHANGE_UNLOAD_1 "Вивід..." + #define MSG_FILAMENT_CHANGE_INSERT_1 "Вставте і нат." + #define MSG_FILAMENT_CHANGE_LOAD_1 "Ввід..." + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 "Екстузія..." + #define MSG_FILAMENT_CHANGE_RESUME_1 "Відновлення..." +#endif // LCD_HEIGHT < 4 + +#endif // LANGUAGE_UK_H diff --git a/Marlin/macros.h b/Marlin/macros.h index 5eec73e343..2859bfeee2 100644 --- a/Marlin/macros.h +++ b/Marlin/macros.h @@ -24,6 +24,9 @@ #define MACROS_H #define NUM_AXIS 4 +#define XYZE 4 +#define ABC 3 +#define XYZ 3 #define FORCE_INLINE __attribute__((always_inline)) inline @@ -33,6 +36,9 @@ #define CRITICAL_SECTION_END SREG = _sreg; #endif +// Clock speed factor +#define CYCLES_PER_MICROSECOND (F_CPU / 1000000UL) // 16 or 20 + // Remove compiler warning on an unused variable #define UNUSED(x) (void) (x) @@ -52,7 +58,8 @@ #endif #define RADIANS(d) ((d)*M_PI/180.0) #define DEGREES(r) ((r)*180.0/M_PI) -#define HYPOT(x,y) sqrt(sq(x)+sq(y)) +#define HYPOT2(x,y) (sq(x)+sq(y)) +#define HYPOT(x,y) sqrt(HYPOT2(x,y)) // Macros to contrain values #define NOLESS(v,n) do{ if (v < n) v = n; }while(0) @@ -71,17 +78,18 @@ #define NUMERIC(a) ((a) >= '0' && '9' >= (a)) #define NUMERIC_SIGNED(a) (NUMERIC(a) || (a) == '-') #define COUNT(a) (sizeof(a)/sizeof(*a)) +#define ZERO(a) memset(a,0,sizeof(a)) // Macros for initializing arrays -#define ARRAY_6(v1, v2, v3, v4, v5, v6, args...) { v1, v2, v3, v4, v5, v6 } -#define ARRAY_5(v1, v2, v3, v4, v5, args...) { v1, v2, v3, v4, v5 } -#define ARRAY_4(v1, v2, v3, v4, args...) { v1, v2, v3, v4 } -#define ARRAY_3(v1, v2, v3, args...) { v1, v2, v3 } -#define ARRAY_2(v1, v2, args...) { v1, v2 } -#define ARRAY_1(v1, args...) { v1 } +#define ARRAY_6(v1, v2, v3, v4, v5, v6, ...) { v1, v2, v3, v4, v5, v6 } +#define ARRAY_5(v1, v2, v3, v4, v5, ...) { v1, v2, v3, v4, v5 } +#define ARRAY_4(v1, v2, v3, v4, ...) { v1, v2, v3, v4 } +#define ARRAY_3(v1, v2, v3, ...) { v1, v2, v3 } +#define ARRAY_2(v1, v2, ...) { v1, v2 } +#define ARRAY_1(v1, ...) { v1 } -#define _ARRAY_N(N, args...) ARRAY_ ##N(args) -#define ARRAY_N(N, args...) _ARRAY_N(N, args) +#define _ARRAY_N(N, ...) ARRAY_ ##N(__VA_ARGS__) +#define ARRAY_N(N, ...) _ARRAY_N(N, __VA_ARGS__) // Macros for adding #define INC_0 1 @@ -118,4 +126,15 @@ #define CEILING(x,y) (((x) + (y) - 1) / (y)) +#define MIN3(a, b, c) min(min(a, b), c) +#define MIN4(a, b, c, d) min(min(a, b), min(c, d)) +#define MAX3(a, b, c) max(max(a, b), c) +#define MAX4(a, b, c, d) max(max(a, b), max(c, d)) + +#define UNEAR_ZERO(x) ((x) < 0.000001) +#define NEAR_ZERO(x) ((x) > -0.000001 && (x) < 0.000001) +#define NEAR(x,y) NEAR_ZERO((x)-(y)) + +#define RECIPROCAL(x) (NEAR_ZERO(x) ? 0.0 : 1.0 / (x)) + #endif //__MACROS_H diff --git a/Marlin/mesh_bed_leveling.cpp b/Marlin/mesh_bed_leveling.cpp index babad8aaae..fa45198c6f 100644 --- a/Marlin/mesh_bed_leveling.cpp +++ b/Marlin/mesh_bed_leveling.cpp @@ -31,7 +31,7 @@ void mesh_bed_leveling::reset() { status = MBL_STATUS_NONE; z_offset = 0; - memset(z_values, 0, sizeof(z_values)); + ZERO(z_values); } #endif // MESH_BED_LEVELING diff --git a/Marlin/mesh_bed_leveling.h b/Marlin/mesh_bed_leveling.h index eb668e1c8e..217cd60340 100644 --- a/Marlin/mesh_bed_leveling.h +++ b/Marlin/mesh_bed_leveling.h @@ -36,54 +36,58 @@ void reset(); - static FORCE_INLINE float get_probe_x(int8_t i) { return MESH_MIN_X + (MESH_X_DIST) * i; } - static FORCE_INLINE float get_probe_y(int8_t i) { return MESH_MIN_Y + (MESH_Y_DIST) * i; } - void set_z(const int8_t px, const int8_t py, const float z) { z_values[py][px] = z; } + static FORCE_INLINE float get_probe_x(const int8_t i) { return MESH_MIN_X + (MESH_X_DIST) * i; } + static FORCE_INLINE float get_probe_y(const int8_t i) { return MESH_MIN_Y + (MESH_Y_DIST) * i; } + void set_z(const int8_t px, const int8_t py, const float &z) { z_values[py][px] = z; } - bool active() { return TEST(status, MBL_STATUS_ACTIVE_BIT); } - void set_active(bool onOff) { if (onOff) SBI(status, MBL_STATUS_ACTIVE_BIT); else CBI(status, MBL_STATUS_ACTIVE_BIT); } - bool has_mesh() { return TEST(status, MBL_STATUS_HAS_MESH_BIT); } - void set_has_mesh(bool onOff) { if (onOff) SBI(status, MBL_STATUS_HAS_MESH_BIT); else CBI(status, MBL_STATUS_HAS_MESH_BIT); } + bool active() const { return TEST(status, MBL_STATUS_ACTIVE_BIT); } + void set_active(const bool onOff) { onOff ? SBI(status, MBL_STATUS_ACTIVE_BIT) : CBI(status, MBL_STATUS_ACTIVE_BIT); } + bool has_mesh() const { return TEST(status, MBL_STATUS_HAS_MESH_BIT); } + void set_has_mesh(const bool onOff) { onOff ? SBI(status, MBL_STATUS_HAS_MESH_BIT) : CBI(status, MBL_STATUS_HAS_MESH_BIT); } - inline void zigzag(int8_t index, int8_t &px, int8_t &py) { + inline void zigzag(const int8_t index, int8_t &px, int8_t &py) const { px = index % (MESH_NUM_X_POINTS); py = index / (MESH_NUM_X_POINTS); if (py & 1) px = (MESH_NUM_X_POINTS - 1) - px; // Zig zag } - void set_zigzag_z(int8_t index, float z) { + void set_zigzag_z(const int8_t index, const float &z) { int8_t px, py; zigzag(index, px, py); set_z(px, py, z); } - int8_t cell_index_x(float x) { - int8_t cx = int(x - (MESH_MIN_X)) / (MESH_X_DIST); + int8_t cell_index_x(const float &x) const { + int8_t cx = (x - (MESH_MIN_X)) * (1.0 / (MESH_X_DIST)); return constrain(cx, 0, (MESH_NUM_X_POINTS) - 2); } - int8_t cell_index_y(float y) { - int8_t cy = int(y - (MESH_MIN_Y)) / (MESH_Y_DIST); + int8_t cell_index_y(const float &y) const { + int8_t cy = (y - (MESH_MIN_Y)) * (1.0 / (MESH_Y_DIST)); return constrain(cy, 0, (MESH_NUM_Y_POINTS) - 2); } - int8_t probe_index_x(float x) { - int8_t px = int(x - (MESH_MIN_X) + (MESH_X_DIST) / 2) / (MESH_X_DIST); + int8_t probe_index_x(const float &x) const { + int8_t px = (x - (MESH_MIN_X) + (MESH_X_DIST) * 0.5) * (1.0 / (MESH_X_DIST)); return (px >= 0 && px < (MESH_NUM_X_POINTS)) ? px : -1; } - int8_t probe_index_y(float y) { - int8_t py = int(y - (MESH_MIN_Y) + (MESH_Y_DIST) / 2) / (MESH_Y_DIST); + int8_t probe_index_y(const float &y) const { + int8_t py = (y - (MESH_MIN_Y) + (MESH_Y_DIST) * 0.5) * (1.0 / (MESH_Y_DIST)); return (py >= 0 && py < (MESH_NUM_Y_POINTS)) ? py : -1; } - float calc_z0(float a0, float a1, float z1, float a2, float z2) { - float delta_z = (z2 - z1) / (a2 - a1); - float delta_a = a0 - a1; + float calc_z0(const float &a0, const float &a1, const float &z1, const float &a2, const float &z2) const { + const float delta_z = (z2 - z1) / (a2 - a1); + const float delta_a = a0 - a1; return z1 + delta_a * delta_z; } - float get_z(float x0, float y0) { + float get_z(const float &x0, const float &y0 + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + , const float &factor + #endif + ) const { int8_t cx = cell_index_x(x0), cy = cell_index_y(y0); if (cx < 0 || cy < 0) return z_offset; @@ -96,7 +100,12 @@ float z0 = calc_z0(y0, get_probe_y(cy), z1, get_probe_y(cy + 1), z2); - return z0 + z_offset; + + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + return z0 * factor + z_offset; + #else + return z0 + z_offset; + #endif } }; diff --git a/Marlin/pins.h b/Marlin/pins.h index 3657675db5..68aaf656fc 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -39,6 +39,8 @@ #include "pins_CHEAPTRONIC.h" #elif MB(SETHI) #include "pins_SETHI.h" +#elif MB(MIGHTYBOARD_REVE) + #include "pins_MIGHTYBOARD_REVE.h" #elif MB(RAMPS_OLD) #include "pins_RAMPS_OLD.h" #elif MB(RAMPS_13_EFB) @@ -131,6 +133,9 @@ #include "pins_MEGATRONICS_2.h" #elif MB(MEGATRONICS_3) #include "pins_MEGATRONICS_3.h" +#elif MB(MEGATRONICS_31) + #define MEGATRONICS_31 + #include "pins_MEGATRONICS_3.h" #elif MB(OMCA_A) #include "pins_OMCA_A.h" #elif MB(OMCA) @@ -214,6 +219,9 @@ #ifndef FAN2_PIN #define FAN2_PIN -1 #endif +#ifndef CONTROLLERFAN_PIN + #define CONTROLLERFAN_PIN -1 +#endif #ifndef HEATER_0_PIN #define HEATER_0_PIN -1 @@ -227,6 +235,9 @@ #ifndef HEATER_3_PIN #define HEATER_3_PIN -1 #endif +#ifndef HEATER_4_PIN + #define HEATER_4_PIN -1 +#endif #ifndef HEATER_BED_PIN #define HEATER_BED_PIN -1 #endif @@ -269,14 +280,35 @@ #define SUICIDE_PIN -1 #endif +#ifndef MAX_EXTRUDERS + #define MAX_EXTRUDERS 4 +#endif + // Marlin needs to account for pins that equal -1 -#define marlinAnalogInputToDigitalPin(p) ((p) == -1 ? -1 : (p) + 0xA0) +#define marlinAnalogInputToDigitalPin(p) ((p) == -1 ? -1 : analogInputToDigitalPin(p)) + +// +// Assign auto fan pins if needed +// +#if !defined(E0_AUTO_FAN_PIN) && defined(ORIG_E0_AUTO_FAN_PIN) + #define E0_AUTO_FAN_PIN ORIG_E0_AUTO_FAN_PIN +#endif +#if !defined(E1_AUTO_FAN_PIN) && defined(ORIG_E1_AUTO_FAN_PIN) + #define E1_AUTO_FAN_PIN ORIG_E1_AUTO_FAN_PIN +#endif +#if !defined(E2_AUTO_FAN_PIN) && defined(ORIG_E2_AUTO_FAN_PIN) + #define E2_AUTO_FAN_PIN ORIG_E2_AUTO_FAN_PIN +#endif +#if !defined(E3_AUTO_FAN_PIN) && defined(ORIG_E3_AUTO_FAN_PIN) + #define E3_AUTO_FAN_PIN ORIG_E3_AUTO_FAN_PIN +#endif // List of pins which to ignore when asked to change by gcode, 0 and 1 are RX and TX, do not mess with those! #define _E0_PINS E0_STEP_PIN, E0_DIR_PIN, E0_ENABLE_PIN, E0_MS1_PIN, E0_MS2_PIN, #define _E1_PINS #define _E2_PINS #define _E3_PINS +#define _E4_PINS #if EXTRUDERS > 1 #undef _E1_PINS @@ -287,24 +319,33 @@ #if EXTRUDERS > 3 #undef _E3_PINS #define _E3_PINS E3_STEP_PIN, E3_DIR_PIN, E3_ENABLE_PIN, + #if EXTRUDERS > 4 + #undef _E4_PINS + #define _E4_PINS E4_STEP_PIN, E4_DIR_PIN, E4_ENABLE_PIN, + #endif #endif #endif #endif -#define _H0_PINS HEATER_0_PIN, EXTRUDER_0_AUTO_FAN_PIN, marlinAnalogInputToDigitalPin(TEMP_0_PIN), +#define _H0_PINS HEATER_0_PIN, E0_AUTO_FAN_PIN, marlinAnalogInputToDigitalPin(TEMP_0_PIN), #define _H1_PINS #define _H2_PINS #define _H3_PINS +#define _H4_PINS #if HOTENDS > 1 #undef _H1_PINS - #define _H1_PINS HEATER_1_PIN, EXTRUDER_1_AUTO_FAN_PIN, marlinAnalogInputToDigitalPin(TEMP_1_PIN), + #define _H1_PINS HEATER_1_PIN, E1_AUTO_FAN_PIN, marlinAnalogInputToDigitalPin(TEMP_1_PIN), #if HOTENDS > 2 #undef _H2_PINS - #define _H2_PINS HEATER_2_PIN, EXTRUDER_2_AUTO_FAN_PIN, marlinAnalogInputToDigitalPin(TEMP_2_PIN), + #define _H2_PINS HEATER_2_PIN, E2_AUTO_FAN_PIN, marlinAnalogInputToDigitalPin(TEMP_2_PIN), #if HOTENDS > 3 #undef _H3_PINS - #define _H3_PINS HEATER_3_PIN, EXTRUDER_3_AUTO_FAN_PIN, marlinAnalogInputToDigitalPin(TEMP_3_PIN), + #define _H3_PINS HEATER_3_PIN, E3_AUTO_FAN_PIN, marlinAnalogInputToDigitalPin(TEMP_3_PIN), + #if HOTENDS > 4 + #undef _H4_PINS + #define _H4_PINS HEATER_4_PIN, marlinAnalogInputToDigitalPin(TEMP_4_PIN), + #endif #endif #endif #elif ENABLED(MIXING_EXTRUDER) @@ -316,6 +357,10 @@ #if MIXING_STEPPERS > 3 #undef _E3_PINS #define _E3_PINS E3_STEP_PIN, E3_DIR_PIN, E3_ENABLE_PIN, + #if MIXING_STEPPERS > 4 + #undef _E4_PINS + #define _E4_PINS E4_STEP_PIN, E4_DIR_PIN, E4_ENABLE_PIN, + #endif #endif #endif #endif @@ -358,7 +403,7 @@ // // Disable unused endstop / probe pins // -#if ENABLED(DISABLE_Z_MIN_PROBE_ENDSTOP) || DISABLED(Z_MIN_PROBE_ENDSTOP) // Allow code to compile regardless of Z_MIN_PROBE_ENDSTOP setting. +#if DISABLED(Z_MIN_PROBE_ENDSTOP) #undef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN -1 #endif @@ -448,25 +493,64 @@ Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, \ Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, Z_MIN_PROBE_PIN, \ PS_ON_PIN, HEATER_BED_PIN, FAN_PIN, FAN1_PIN, FAN2_PIN, CONTROLLERFAN_PIN, \ - _E0_PINS _E1_PINS _E2_PINS _E3_PINS BED_PINS \ - _H0_PINS _H1_PINS _H2_PINS _H3_PINS \ + _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS BED_PINS \ + _H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS \ _X2_PINS _Y2_PINS _Z2_PINS \ X_MS1_PIN, X_MS2_PIN, Y_MS1_PIN, Y_MS2_PIN, Z_MS1_PIN, Z_MS2_PIN \ } #define HAS_DIGIPOTSS (PIN_EXISTS(DIGIPOTSS)) +/** + * Define SPI Pins: SCK, MISO, MOSI, SS + */ +#if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) + #define AVR_SCK_PIN 13 + #define AVR_MISO_PIN 12 + #define AVR_MOSI_PIN 11 + #define AVR_SS_PIN 10 +#elif defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__) + #define AVR_SCK_PIN 7 + #define AVR_MISO_PIN 6 + #define AVR_MOSI_PIN 5 + #define AVR_SS_PIN 4 +#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) + #define AVR_SCK_PIN 52 + #define AVR_MISO_PIN 50 + #define AVR_MOSI_PIN 51 + #define AVR_SS_PIN 53 +#elif defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB647__) + #if ENABLED(AT90USBxx_TEENSYPP_ASSIGNMENTS) + // Teensy pin assignments + #define AVR_SCK_PIN 21 + #define AVR_MISO_PIN 23 + #define AVR_MOSI_PIN 22 + #define AVR_SS_PIN 20 + #else + // Traditional pin assignments + #define AVR_SCK_PIN 9 + #define AVR_MISO_PIN 11 + #define AVR_MOSI_PIN 10 + #define AVR_SS_PIN 8 + #endif +#elif defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) + #define AVR_SCK_PIN 10 + #define AVR_MISO_PIN 12 + #define AVR_MOSI_PIN 11 + #define AVR_SS_PIN 16 +#endif + #ifndef SCK_PIN - #define SCK_PIN SCK + #define SCK_PIN AVR_SCK_PIN #endif #ifndef MISO_PIN - #define MISO_PIN MISO + #define MISO_PIN AVR_MISO_PIN #endif #ifndef MOSI_PIN - #define MOSI_PIN MOSI + #define MOSI_PIN AVR_MOSI_PIN #endif #ifndef SS_PIN - #define SS_PIN SS + #define SS_PIN AVR_SS_PIN #endif #endif //__PINS_H diff --git a/Marlin/pinsDebug.h b/Marlin/pinsDebug.h new file mode 100644 index 0000000000..eb5584d65e --- /dev/null +++ b/Marlin/pinsDebug.h @@ -0,0 +1,945 @@ +/** + * 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 . + * + */ + +bool endstop_monitor_flag = false; + +#define NAME_FORMAT "%-28s" // one place to specify the format of all the sources of names + // "-" left justify, "28" minimum width of name, pad with blanks + +#define _PIN_SAY(NAME) { sprintf(buffer, NAME_FORMAT, NAME); SERIAL_ECHO(buffer); return true; } +#define PIN_SAY(NAME) if (pin == NAME) _PIN_SAY(#NAME); + +#define _ANALOG_PIN_SAY(NAME) { sprintf(buffer, NAME_FORMAT, NAME); SERIAL_ECHO(buffer); pin_is_analog = true; return true; } +#define ANALOG_PIN_SAY(NAME) if (pin == analogInputToDigitalPin(NAME)) _ANALOG_PIN_SAY(#NAME); + +#define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && ((P) <= analogInputToDigitalPin(15) || (P) <= analogInputToDigitalPin(5))) + +int digitalRead_mod(int8_t pin) { // same as digitalRead except the PWM stop section has been removed + uint8_t port = digitalPinToPort(pin); + return (port != NOT_A_PIN) && (*portInputRegister(port) & digitalPinToBitMask(pin)) ? HIGH : LOW; +} + +/** + * Report pin name for a given fastio digital pin index + */ +static bool report_pin_name(int8_t pin, bool &pin_is_analog) { + + char buffer[30]; // for the sprintf statements + pin_is_analog = false; // default to digital pin + + if (IS_ANALOG(pin)) { + sprintf(buffer, "(A%2d) ", int(pin - analogInputToDigitalPin(0))); + SERIAL_ECHO(buffer); + } + else SERIAL_ECHOPGM(" "); + + #if defined(RXD) && RXD >= 0 + if (pin == 0) { sprintf(buffer, NAME_FORMAT, "RXD"); SERIAL_ECHO(buffer); return true; } + #endif + + #if defined(TXD) && TXD >= 0 + if (pin == 1) { sprintf(buffer, NAME_FORMAT, "TXD"); SERIAL_ECHO(buffer); return true; } + #endif + + // Pin list updated from 7 OCT RCBugfix branch - max length of pin name is 24 + #if defined(__FD) && __FD >= 0 + PIN_SAY(__FD) + #endif + #if defined(__FS) && __FS >= 0 + PIN_SAY(__FS) + #endif + #if defined(__GD) && __GD >= 0 + PIN_SAY(__GD) + #endif + #if defined(__GS) && __GS >= 0 + PIN_SAY(__GS) + #endif + + #if PIN_EXISTS(AVR_MISO) + PIN_SAY(AVR_MISO_PIN); + #endif + #if PIN_EXISTS(AVR_MOSI) + PIN_SAY(AVR_MOSI_PIN); + #endif + #if PIN_EXISTS(AVR_SCK) + PIN_SAY(AVR_SCK_PIN); + #endif + #if PIN_EXISTS(AVR_SS) + PIN_SAY(AVR_SS_PIN); + #endif + #if PIN_EXISTS(BEEPER) + PIN_SAY(BEEPER_PIN); + #endif + #if defined(BTN_CENTER) && BTN_CENTER >= 0 + PIN_SAY(BTN_CENTER); + #endif + #if defined(BTN_DOWN) && BTN_DOWN >= 0 + PIN_SAY(BTN_DOWN); + #endif + #if defined(BTN_DWN) && BTN_DWN >= 0 + PIN_SAY(BTN_DWN); + #endif + #if defined(BTN_EN1) && BTN_EN1 >= 0 + PIN_SAY(BTN_EN1); + #endif + #if defined(BTN_EN2) && BTN_EN2 >= 0 + PIN_SAY(BTN_EN2); + #endif + #if defined(BTN_ENC) && BTN_ENC >= 0 + PIN_SAY(BTN_ENC); + #endif + #if defined(BTN_HOME) && BTN_HOME >= 0 + PIN_SAY(BTN_HOME); + #endif + #if defined(BTN_LEFT) && BTN_LEFT >= 0 + PIN_SAY(BTN_LEFT); + #endif + #if defined(BTN_LFT) && BTN_LFT >= 0 + PIN_SAY(BTN_LFT); + #endif + #if defined(BTN_RIGHT) && BTN_RIGHT >= 0 + PIN_SAY(BTN_RIGHT); + #endif + #if defined(BTN_RT) && BTN_RT >= 0 + PIN_SAY(BTN_RT); + #endif + #if defined(BTN_UP) && BTN_UP >= 0 + PIN_SAY(BTN_UP); + #endif + #if PIN_EXISTS(CONTROLLERFAN) + PIN_SAY(CONTROLLERFAN_PIN); + #endif + #if PIN_EXISTS(DAC_DISABLE) + PIN_SAY(DAC_DISABLE_PIN); + #endif + #if defined(DAC_STEPPER_GAIN) && DAC_STEPPER_GAIN >= 0 + PIN_SAY(DAC_STEPPER_GAIN); + #endif + #if defined(DAC_STEPPER_VREF) && DAC_STEPPER_VREF >= 0 + PIN_SAY(DAC_STEPPER_VREF); + #endif + #if PIN_EXISTS(DEBUG) + PIN_SAY(DEBUG_PIN); + #endif + #if PIN_EXISTS(DIGIPOTSS) + PIN_SAY(DIGIPOTSS_PIN); + #endif + #if defined(DOGLCD_A0) && DOGLCD_A0 >= 0 + PIN_SAY(DOGLCD_A0); + #endif + #if defined(DOGLCD_CS) && DOGLCD_CS >= 0 + PIN_SAY(DOGLCD_CS); + #endif + #if defined(DOGLCD_MOSI) && DOGLCD_MOSI >= 0 + PIN_SAY(DOGLCD_MOSI); + #endif + #if defined(DOGLCD_SCK) && DOGLCD_SCK >= 0 + PIN_SAY(DOGLCD_SCK); + #endif + #if PIN_EXISTS(E0_ATT) + PIN_SAY(E0_ATT_PIN); + #endif + #if PIN_EXISTS(E0_AUTO_FAN) + PIN_SAY(E0_AUTO_FAN_PIN); + #endif + #if PIN_EXISTS(E1_AUTO_FAN) + PIN_SAY(E1_AUTO_FAN_PIN); + #endif + #if PIN_EXISTS(E2_AUTO_FAN) + PIN_SAY(E2_AUTO_FAN_PIN); + #endif + #if PIN_EXISTS(E3_AUTO_FAN) + PIN_SAY(E3_AUTO_FAN_PIN); + #endif + #if PIN_EXISTS(E0_DIR) + PIN_SAY(E0_DIR_PIN); + #endif + #if PIN_EXISTS(E0_ENABLE) + PIN_SAY(E0_ENABLE_PIN); + #endif + #if PIN_EXISTS(E0_MS1) + PIN_SAY(E0_MS1_PIN); + #endif + #if PIN_EXISTS(E0_MS2) + PIN_SAY(E0_MS2_PIN); + #endif + #if PIN_EXISTS(E0_STEP) + PIN_SAY(E0_STEP_PIN); + #endif + #if PIN_EXISTS(E1_DIR) + PIN_SAY(E1_DIR_PIN); + #endif + #if PIN_EXISTS(E1_ENABLE) + PIN_SAY(E1_ENABLE_PIN); + #endif + #if PIN_EXISTS(E1_MS1) + PIN_SAY(E1_MS1_PIN); + #endif + #if PIN_EXISTS(E1_MS2) + PIN_SAY(E1_MS2_PIN); + #endif + #if PIN_EXISTS(E1_STEP) + PIN_SAY(E1_STEP_PIN); + #endif + #if PIN_EXISTS(E2_DIR) + PIN_SAY(E2_DIR_PIN); + #endif + #if PIN_EXISTS(E2_ENABLE) + PIN_SAY(E2_ENABLE_PIN); + #endif + #if PIN_EXISTS(E2_STEP) + PIN_SAY(E2_STEP_PIN); + #endif + #if PIN_EXISTS(E3_DIR) + PIN_SAY(E3_DIR_PIN); + #endif + #if PIN_EXISTS(E3_ENABLE) + PIN_SAY(E3_ENABLE_PIN); + #endif + #if PIN_EXISTS(E3_STEP) + PIN_SAY(E3_STEP_PIN); + #endif + #if PIN_EXISTS(E4_DIR) + PIN_SAY(E4_DIR_PIN); + #endif + #if PIN_EXISTS(E4_ENABLE) + PIN_SAY(E4_ENABLE_PIN); + #endif + #if PIN_EXISTS(E4_STEP) + PIN_SAY(E4_STEP_PIN); + #endif + #if defined(encrot1) && encrot1 >= 0 + PIN_SAY(encrot1); + #endif + #if defined(encrot2) && encrot2 >= 0 + PIN_SAY(encrot2); + #endif + #if defined(encrot3) && encrot3 >= 0 + PIN_SAY(encrot3); + #endif + #if defined(EXT_AUX_A0_IO) && EXT_AUX_A0_IO >= 0 + PIN_SAY(EXT_AUX_A0_IO); + #endif + #if defined(EXT_AUX_A1) && EXT_AUX_A1 >= 0 + PIN_SAY(EXT_AUX_A1); + #endif + #if defined(EXT_AUX_A1_IO) && EXT_AUX_A1_IO >= 0 + PIN_SAY(EXT_AUX_A1_IO); + #endif + #if defined(EXT_AUX_A2) && EXT_AUX_A2 >= 0 + PIN_SAY(EXT_AUX_A2); + #endif + #if defined(EXT_AUX_A2_IO) && EXT_AUX_A2_IO >= 0 + PIN_SAY(EXT_AUX_A2_IO); + #endif + #if defined(EXT_AUX_A3) && EXT_AUX_A3 >= 0 + PIN_SAY(EXT_AUX_A3); + #endif + #if defined(EXT_AUX_A3_IO) && EXT_AUX_A3_IO >= 0 + PIN_SAY(EXT_AUX_A3_IO); + #endif + #if defined(EXT_AUX_A4) && EXT_AUX_A4 >= 0 + PIN_SAY(EXT_AUX_A4); + #endif + #if defined(EXT_AUX_A4_IO) && EXT_AUX_A4_IO >= 0 + PIN_SAY(EXT_AUX_A4_IO); + #endif + #if defined(EXT_AUX_PWM_D24) && EXT_AUX_PWM_D24 >= 0 + PIN_SAY(EXT_AUX_PWM_D24); + #endif + #if defined(EXT_AUX_RX1_D2) && EXT_AUX_RX1_D2 >= 0 + PIN_SAY(EXT_AUX_RX1_D2); + #endif + #if defined(EXT_AUX_SDA_D1) && EXT_AUX_SDA_D1 >= 0 + PIN_SAY(EXT_AUX_SDA_D1); + #endif + #if defined(EXT_AUX_TX1_D3) && EXT_AUX_TX1_D3 >= 0 + PIN_SAY(EXT_AUX_TX1_D3); + #endif + + #if PIN_EXISTS(FAN) + PIN_SAY(FAN_PIN); + #endif + #if PIN_EXISTS(FAN1) + PIN_SAY(FAN1_PIN); + #endif + #if PIN_EXISTS(FAN2) + PIN_SAY(FAN2_PIN); + #endif + #if PIN_EXISTS(FIL_RUNOUT) + PIN_SAY(FIL_RUNOUT_PIN); + #endif + #if PIN_EXISTS(FILWIDTH) + ANALOG_PIN_SAY(FILWIDTH_PIN); + #endif + #if defined(GEN7_VERSION) && GEN7_VERSION >= 0 + PIN_SAY(GEN7_VERSION); + #endif + #if PIN_EXISTS(HEATER_0) + PIN_SAY(HEATER_0_PIN); + #endif + #if PIN_EXISTS(HEATER_1) + PIN_SAY(HEATER_1_PIN); + #endif + #if PIN_EXISTS(HEATER_2) + PIN_SAY(HEATER_2_PIN); + #endif + #if PIN_EXISTS(HEATER_3) + PIN_SAY(HEATER_3_PIN); + #endif + #if PIN_EXISTS(HEATER_4) + PIN_SAY(HEATER_4_PIN); + #endif + #if PIN_EXISTS(HEATER_5) + PIN_SAY(HEATER_5_PIN); + #endif + #if PIN_EXISTS(HEATER_6) + PIN_SAY(HEATER_6_PIN); + #endif + #if PIN_EXISTS(HEATER_7) + PIN_SAY(HEATER_7_PIN); + #endif + #if PIN_EXISTS(HEATER_BED) + PIN_SAY(HEATER_BED_PIN); + #endif + #if defined(I2C_SCL) && I2C_SCL >= 0 + PIN_SAY(I2C_SCL); + #endif + #if defined(I2C_SDA) && I2C_SDA >= 0 + PIN_SAY(I2C_SDA); + #endif + #if PIN_EXISTS(KILL) + PIN_SAY(KILL_PIN); + #endif + #if PIN_EXISTS(LCD_BACKLIGHT) + PIN_SAY(LCD_BACKLIGHT_PIN); + #endif + #if defined(LCD_CONTRAST) && LCD_CONTRAST >= 0 + PIN_SAY(LCD_CONTRAST); + #endif + #if defined(LCD_PINS_D4) && LCD_PINS_D4 >= 0 + PIN_SAY(LCD_PINS_D4); + #endif + #if defined(LCD_PINS_D5) && LCD_PINS_D5 >= 0 + PIN_SAY(LCD_PINS_D5); + #endif + #if defined(LCD_PINS_D6) && LCD_PINS_D6 >= 0 + PIN_SAY(LCD_PINS_D6); + #endif + #if defined(LCD_PINS_D7) && LCD_PINS_D7 >= 0 + PIN_SAY(LCD_PINS_D7); + #endif + #if defined(LCD_PINS_ENABLE) && LCD_PINS_ENABLE >= 0 + PIN_SAY(LCD_PINS_ENABLE); + #endif + #if defined(LCD_PINS_RS) && LCD_PINS_RS >= 0 + PIN_SAY(LCD_PINS_RS); + #endif + #if defined(LCD_SDSS) && LCD_SDSS >= 0 + PIN_SAY(LCD_SDSS); + #endif + #if PIN_EXISTS(LED) + PIN_SAY(LED_PIN); + #endif + #if PIN_EXISTS(CASE_LIGHT) + PIN_SAY(CASE_LIGHT_PIN); + #endif + #if PIN_EXISTS(MAIN_VOLTAGE_MEASURE) + PIN_SAY(MAIN_VOLTAGE_MEASURE_PIN); + #endif + #if defined(MAX6675_SS) && MAX6675_SS >= 0 + PIN_SAY(MAX6675_SS); + #endif + #if PIN_EXISTS(MISO) + PIN_SAY(MISO_PIN); + #endif + #if PIN_EXISTS(MOSFET_D) + PIN_SAY(MOSFET_D_PIN); + #endif + #if PIN_EXISTS(MOSI) + PIN_SAY(MOSI_PIN); + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) + PIN_SAY(MOTOR_CURRENT_PWM_E_PIN); + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) + PIN_SAY(MOTOR_CURRENT_PWM_XY_PIN); + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) + PIN_SAY(MOTOR_CURRENT_PWM_Z_PIN); + #endif + #if defined(NUM_TLCS) && NUM_TLCS >= 0 + PIN_SAY(NUM_TLCS); + #endif + #if PIN_EXISTS(PHOTOGRAPH) + PIN_SAY(PHOTOGRAPH_PIN); + #endif + #if PIN_EXISTS(PS_ON) + PIN_SAY(PS_ON_PIN); + #endif + #if PIN_EXISTS(RAMPS_D10) + PIN_SAY(RAMPS_D10_PIN); + #endif + #if PIN_EXISTS(RAMPS_D8) + PIN_SAY(RAMPS_D8_PIN); + #endif + #if PIN_EXISTS(RAMPS_D9) + PIN_SAY(RAMPS_D9_PIN); + #endif + #if PIN_EXISTS(RX_ENABLE) + PIN_SAY(RX_ENABLE_PIN); + #endif + #if PIN_EXISTS(SAFETY_TRIGGERED) + PIN_SAY(SAFETY_TRIGGERED_PIN); + #endif + #if PIN_EXISTS(SCK) + PIN_SAY(SCK_PIN); + #endif + #if defined(SCL) && SCL >= 0 + PIN_SAY(SCL); + #endif + #if PIN_EXISTS(SD_DETECT) + PIN_SAY(SD_DETECT_PIN); + #endif + #if defined(SDA) && SDA >= 0 + PIN_SAY(SDA); + #endif + #if defined(SDPOWER) && SDPOWER >= 0 + PIN_SAY(SDPOWER); + #endif + #if defined(SDSS) && SDSS >= 0 + PIN_SAY(SDSS); + #endif + #if PIN_EXISTS(SERVO0) + PIN_SAY(SERVO0_PIN); + #endif + #if PIN_EXISTS(SERVO1) + PIN_SAY(SERVO1_PIN); + #endif + #if PIN_EXISTS(SERVO2) + PIN_SAY(SERVO2_PIN); + #endif + #if PIN_EXISTS(SERVO3) + PIN_SAY(SERVO3_PIN); + #endif + #if defined(SHIFT_CLK) && SHIFT_CLK >= 0 + PIN_SAY(SHIFT_CLK); + #endif + #if defined(SHIFT_EN) && SHIFT_EN >= 0 + PIN_SAY(SHIFT_EN); + #endif + #if defined(SHIFT_LD) && SHIFT_LD >= 0 + PIN_SAY(SHIFT_LD); + #endif + #if defined(SHIFT_OUT) && SHIFT_OUT >= 0 + PIN_SAY(SHIFT_OUT); + #endif + #if PIN_EXISTS(SLED) + PIN_SAY(SLED_PIN); + #endif + #if PIN_EXISTS(SLEEP_WAKE) + PIN_SAY(SLEEP_WAKE_PIN); + #endif + #if PIN_EXISTS(SOL1) + PIN_SAY(SOL1_PIN); + #endif + #if PIN_EXISTS(SOL2) + PIN_SAY(SOL2_PIN); + #endif + #if PIN_EXISTS(SPINDLE_ENABLE) + PIN_SAY(SPINDLE_ENABLE_PIN); + #endif + #if PIN_EXISTS(SPINDLE_SPEED) + PIN_SAY(SPINDLE_SPEED_PIN); + #endif + #if PIN_EXISTS(SS) + PIN_SAY(SS_PIN); + #endif + #if PIN_EXISTS(STAT_LED_BLUE) + PIN_SAY(STAT_LED_BLUE_PIN); + #endif + #if PIN_EXISTS(STAT_LED_RED) + PIN_SAY(STAT_LED_RED_PIN); + #endif + #if PIN_EXISTS(STEPPER_RESET) + PIN_SAY(STEPPER_RESET_PIN); + #endif + #if PIN_EXISTS(SUICIDE) + PIN_SAY(SUICIDE_PIN); + #endif + #if defined(TC1) && TC1 >= 0 + ANALOG_PIN_SAY(TC1); + #endif + #if defined(TC2) && TC2 >= 0 + ANALOG_PIN_SAY(TC2); + #endif + #if PIN_EXISTS(TEMP_0) + ANALOG_PIN_SAY(TEMP_0_PIN); + #endif + #if PIN_EXISTS(TEMP_1) + ANALOG_PIN_SAY(TEMP_1_PIN); + #endif + #if PIN_EXISTS(TEMP_2) + ANALOG_PIN_SAY(TEMP_2_PIN); + #endif + #if PIN_EXISTS(TEMP_3) + ANALOG_PIN_SAY(TEMP_3_PIN); + #endif + #if PIN_EXISTS(TEMP_4) + ANALOG_PIN_SAY(TEMP_4_PIN); + #endif + #if PIN_EXISTS(TEMP_BED) + ANALOG_PIN_SAY(TEMP_BED_PIN); + #endif + #if PIN_EXISTS(TEMP_X) + ANALOG_PIN_SAY(TEMP_X_PIN); + #endif + #if defined(TLC_BLANK_BIT) && TLC_BLANK_BIT >= 0 + PIN_SAY(TLC_BLANK_BIT); + #endif + #if PIN_EXISTS(TLC_BLANK) + PIN_SAY(TLC_BLANK_PIN); + #endif + #if defined(TLC_CLOCK_BIT) && TLC_CLOCK_BIT >= 0 + PIN_SAY(TLC_CLOCK_BIT); + #endif + #if PIN_EXISTS(TLC_CLOCK) + PIN_SAY(TLC_CLOCK_PIN); + #endif + #if defined(TLC_DATA_BIT) && TLC_DATA_BIT >= 0 + PIN_SAY(TLC_DATA_BIT); + #endif + #if PIN_EXISTS(TLC_DATA) + PIN_SAY(TLC_DATA_PIN); + #endif + #if PIN_EXISTS(TLC_XLAT) + PIN_SAY(TLC_XLAT_PIN); + #endif + #if PIN_EXISTS(TX_ENABLE) + PIN_SAY(TX_ENABLE_PIN); + #endif + #if defined(UNUSED_PWM) && UNUSED_PWM >= 0 + PIN_SAY(UNUSED_PWM); + #endif + #if PIN_EXISTS(X_ATT) + PIN_SAY(X_ATT_PIN); + #endif + #if PIN_EXISTS(X_DIR) + PIN_SAY(X_DIR_PIN); + #endif + #if PIN_EXISTS(X_ENABLE) + PIN_SAY(X_ENABLE_PIN); + #endif + #if PIN_EXISTS(X_MAX) + PIN_SAY(X_MAX_PIN); + #endif + #if PIN_EXISTS(X_MIN) + PIN_SAY(X_MIN_PIN); + #endif + #if PIN_EXISTS(X_MS1) + PIN_SAY(X_MS1_PIN); + #endif + #if PIN_EXISTS(X_MS2) + PIN_SAY(X_MS2_PIN); + #endif + #if PIN_EXISTS(X_STEP) + PIN_SAY(X_STEP_PIN); + #endif + #if PIN_EXISTS(X_STOP) + PIN_SAY(X_STOP_PIN); + #endif + #if PIN_EXISTS(X2_DIR) + PIN_SAY(X2_DIR_PIN); + #endif + #if PIN_EXISTS(X2_ENABLE) + PIN_SAY(X2_ENABLE_PIN); + #endif + #if PIN_EXISTS(X2_STEP) + PIN_SAY(X2_STEP_PIN); + #endif + #if PIN_EXISTS(Y_ATT) + PIN_SAY(Y_ATT_PIN); + #endif + #if PIN_EXISTS(Y_DIR) + PIN_SAY(Y_DIR_PIN); + #endif + #if PIN_EXISTS(Y_ENABLE) + PIN_SAY(Y_ENABLE_PIN); + #endif + #if PIN_EXISTS(Y_MAX) + PIN_SAY(Y_MAX_PIN); + #endif + #if PIN_EXISTS(Y_MIN) + PIN_SAY(Y_MIN_PIN); + #endif + #if PIN_EXISTS(Y_MS1) + PIN_SAY(Y_MS1_PIN); + #endif + #if PIN_EXISTS(Y_MS2) + PIN_SAY(Y_MS2_PIN); + #endif + #if PIN_EXISTS(Y_STEP) + PIN_SAY(Y_STEP_PIN); + #endif + #if PIN_EXISTS(Y_STOP) + PIN_SAY(Y_STOP_PIN); + #endif + #if PIN_EXISTS(Y2_DIR) + PIN_SAY(Y2_DIR_PIN); + #endif + #if PIN_EXISTS(Y2_ENABLE) + PIN_SAY(Y2_ENABLE_PIN); + #endif + #if PIN_EXISTS(Y2_STEP) + PIN_SAY(Y2_STEP_PIN); + #endif + #if PIN_EXISTS(Z_ATT) + PIN_SAY(Z_ATT_PIN); + #endif + #if PIN_EXISTS(Z_DIR) + PIN_SAY(Z_DIR_PIN); + #endif + #if PIN_EXISTS(Z_ENABLE) + PIN_SAY(Z_ENABLE_PIN); + #endif + #if PIN_EXISTS(Z_MAX) + PIN_SAY(Z_MAX_PIN); + #endif + #if PIN_EXISTS(Z_MIN) + PIN_SAY(Z_MIN_PIN); + #endif + #if PIN_EXISTS(Z_MIN_PROBE) + PIN_SAY(Z_MIN_PROBE_PIN); + #endif + #if PIN_EXISTS(Z_MS1) + PIN_SAY(Z_MS1_PIN); + #endif + #if PIN_EXISTS(Z_MS2) + PIN_SAY(Z_MS2_PIN); + #endif + #if PIN_EXISTS(Z_STEP) + PIN_SAY(Z_STEP_PIN); + #endif + #if PIN_EXISTS(Z_STOP) + PIN_SAY(Z_STOP_PIN); + #endif + #if PIN_EXISTS(Z2_DIR) + PIN_SAY(Z2_DIR_PIN); + #endif + #if PIN_EXISTS(Z2_ENABLE) + PIN_SAY(Z2_ENABLE_PIN); + #endif + #if PIN_EXISTS(Z2_STEP) + PIN_SAY(Z2_STEP_PIN); + #endif + + sprintf(buffer, NAME_FORMAT, " "); + SERIAL_ECHO(buffer); + + return false; +} // report_pin_name + +#define PWM_PRINT(V) do{ sprintf(buffer, "PWM: %4d", V); SERIAL_ECHO(buffer); }while(0) +#define PWM_CASE(N,Z) \ + case TIMER##N##Z: \ + if (TCCR##N##A & (_BV(COM##N##Z##1) | _BV(COM##N##Z##0))) { \ + PWM_PRINT(OCR##N##Z); \ + return true; \ + } else return false + +/** + * Print a pin's PWM status. + * Return true if it's currently a PWM pin. + */ +static bool pwm_status(uint8_t pin) { + char buffer[20]; // for the sprintf statements + + switch(digitalPinToTimer(pin)) { + + #if defined(TCCR0A) && defined(COM0A1) + PWM_CASE(0,A); + PWM_CASE(0,B); + #endif + + #if defined(TCCR1A) && defined(COM1A1) + PWM_CASE(1,A); + PWM_CASE(1,B); + PWM_CASE(1,C); + #endif + + #if defined(TCCR2A) && defined(COM2A1) + PWM_CASE(2,A); + PWM_CASE(2,B); + #endif + + #if defined(TCCR3A) && defined(COM3A1) + PWM_CASE(3,A); + PWM_CASE(3,B); + PWM_CASE(3,C); + #endif + + #ifdef TCCR4A + PWM_CASE(4,A); + PWM_CASE(4,B); + PWM_CASE(4,C); + #endif + + #if defined(TCCR5A) && defined(COM5A1) + PWM_CASE(5,A); + PWM_CASE(5,B); + PWM_CASE(5,C); + #endif + + case NOT_ON_TIMER: + default: + return false; + } + SERIAL_PROTOCOLPGM(" "); +} // pwm_status + +#define WGM_MAKE3(N) (((TCCR##N##B & _BV(WGM##N##2)) >> 1) | (TCCR##N##A & (_BV(WGM##N##0) | _BV(WGM##N##1)))) +#define WGM_MAKE4(N) (WGM_MAKE3(N) | (TCCR##N##B & _BV(WGM##N##3)) >> 1) +#define TIMER_PREFIX(T,L,N) do{ \ + WGM = WGM_MAKE##N(T); \ + SERIAL_PROTOCOLPGM(" TIMER"); \ + SERIAL_PROTOCOLPGM(STRINGIFY(T) STRINGIFY(L)); \ + SERIAL_PROTOCOLPAIR(" WGM: ", WGM); \ + SERIAL_PROTOCOLPAIR(" TIMSK" STRINGIFY(T) ": ", TIMSK##T); \ + }while(0) + +#define WGM_TEST1 (WGM == 0 || WGM == 2 || WGM == 4 || WGM == 6) +#define WGM_TEST2 (WGM == 0 || WGM == 4 || WGM == 12 || WGM == 13) + +static void err_is_counter() { + SERIAL_PROTOCOLPGM(" Can't be used as a PWM because of counter mode"); +} +static void err_is_interrupt() { + SERIAL_PROTOCOLPGM(" Can't be used as a PWM because it's being used as an interrupt"); +} +static void err_prob_interrupt() { + SERIAL_PROTOCOLPGM(" Probably can't be used as a PWM because counter/timer is being used as an interrupt"); +} +static void can_be_used() { SERIAL_PROTOCOLPGM(" can be used as PWM "); } + +static void pwm_details(uint8_t pin) { + + uint8_t WGM; + + switch(digitalPinToTimer(pin)) { + + #if defined(TCCR0A) && defined(COM0A1) + case TIMER0A: + TIMER_PREFIX(0,A,3); + if (WGM_TEST1) err_is_counter(); + else if (TEST(TIMSK0, OCIE0A)) err_is_interrupt(); + else if (TEST(TIMSK0, TOIE0)) err_prob_interrupt(); + else can_be_used(); + break; + case TIMER0B: + TIMER_PREFIX(0,B,3); + if (WGM_TEST1) err_is_counter(); + else if (TEST(TIMSK0, OCIE0B)) err_is_interrupt(); + else if (TEST(TIMSK0, TOIE0)) err_prob_interrupt(); + else can_be_used(); + break; + #endif + + #if defined(TCCR1A) && defined(COM1A1) + case TIMER1A: + TIMER_PREFIX(1,A,4); + if (WGM_TEST2) err_is_counter(); + else if (TEST(TIMSK1, OCIE1A)) err_is_interrupt(); + else if (TIMSK1 & (_BV(TOIE1) | _BV(ICIE1))) err_prob_interrupt(); + else can_be_used(); + break; + case TIMER1B: + TIMER_PREFIX(1,B,4); + if (WGM_TEST2) err_is_counter(); + else if (TEST(TIMSK1, OCIE1B)) err_is_interrupt(); + else if (TIMSK1 & (_BV(TOIE1) | _BV(ICIE1))) err_prob_interrupt(); + else can_be_used(); + break; + case TIMER1C: + TIMER_PREFIX(1,C,4); + if (WGM_TEST2) err_is_counter(); + else if (TEST(TIMSK1, OCIE1C)) err_is_interrupt(); + else if (TIMSK1 & (_BV(TOIE1) | _BV(ICIE1))) err_prob_interrupt(); + else can_be_used(); + break; + #endif + + #if defined(TCCR2A) && defined(COM2A1) + case TIMER2A: + TIMER_PREFIX(2,A,3); + if (WGM_TEST1) err_is_counter(); + else if (TIMSK2 & (_BV(TOIE2) | _BV(OCIE2A))) err_is_interrupt(); + else if (TEST(TIMSK2, TOIE2)) err_prob_interrupt(); + else can_be_used(); + break; + case TIMER2B: + TIMER_PREFIX(2,B,3); + if (WGM_TEST1) err_is_counter(); + else if (TEST(TIMSK2, OCIE2B)) err_is_interrupt(); + else if (TEST(TIMSK2, TOIE2)) err_prob_interrupt(); + else can_be_used(); + break; + #endif + + #if defined(TCCR3A) && defined(COM3A1) + case TIMER3A: + TIMER_PREFIX(3,A,3); + if (WGM_TEST2) err_is_counter(); + else if (TEST(TIMSK3, OCIE3A)) err_is_interrupt(); + else if (TIMSK3 & (_BV(TOIE3) | _BV(ICIE3))) err_prob_interrupt(); + else can_be_used(); + break; + case TIMER3B: + TIMER_PREFIX(3,B,3); + if (WGM_TEST2) err_is_counter(); + else if (TEST(TIMSK3, OCIE3B)) err_is_interrupt(); + else if (TIMSK3 & (_BV(TOIE3) | _BV(ICIE3))) err_prob_interrupt(); + else can_be_used(); + break; + case TIMER3C: + TIMER_PREFIX(3,C,3); + if (WGM_TEST2) err_is_counter(); + else if (TEST(TIMSK3, OCIE3C)) err_is_interrupt(); + else if (TIMSK3 & (_BV(TOIE3) | _BV(ICIE3))) err_prob_interrupt(); + else can_be_used(); + break; + #endif + + #ifdef TCCR4A + case TIMER4A: + TIMER_PREFIX(4,A,4); + if (WGM_TEST2) err_is_counter(); + else if (TEST(TIMSK4, OCIE4A)) err_is_interrupt(); + else if (TIMSK4 & (_BV(TOIE4) | _BV(ICIE4))) err_prob_interrupt(); + else can_be_used(); + break; + case TIMER4B: + TIMER_PREFIX(4,B,4); + if (WGM_TEST2) err_is_counter(); + else if (TEST(TIMSK4, OCIE4B)) err_is_interrupt(); + else if (TIMSK4 & (_BV(TOIE4) | _BV(ICIE4))) err_prob_interrupt(); + else can_be_used(); + break; + case TIMER4C: + TIMER_PREFIX(4,C,4); + if (WGM_TEST2) err_is_counter(); + else if (TEST(TIMSK4, OCIE4C)) err_is_interrupt(); + else if (TIMSK4 & (_BV(TOIE4) | _BV(ICIE4))) err_prob_interrupt(); + else can_be_used(); + break; + #endif + + #if defined(TCCR5A) && defined(COM5A1) + case TIMER5A: + TIMER_PREFIX(5,A,4); + if (WGM_TEST2) err_is_counter(); + else if (TEST(TIMSK5, OCIE5A)) err_is_interrupt(); + else if (TIMSK5 & (_BV(TOIE5) | _BV(ICIE5))) err_prob_interrupt(); + else can_be_used(); + break; + case TIMER5B: + TIMER_PREFIX(5,B,4); + if (WGM_TEST2) err_is_counter(); + else if (TEST(TIMSK5, OCIE5B)) err_is_interrupt(); + else if (TIMSK5 & (_BV(TOIE5) | _BV(ICIE5))) err_prob_interrupt(); + else can_be_used(); + break; + case TIMER5C: + TIMER_PREFIX(5,C,4); + if (WGM_TEST2) err_is_counter(); + else if (TEST(TIMSK5, OCIE5C)) err_is_interrupt(); + else if (TIMSK5 & (_BV(TOIE5) | _BV(ICIE5))) err_prob_interrupt(); + else can_be_used(); + break; + #endif + + case NOT_ON_TIMER: break; + + } + SERIAL_PROTOCOLPGM(" "); +} // pwm_details + +inline void report_pin_state(int8_t pin) { + SERIAL_ECHO((int)pin); + SERIAL_CHAR(' '); + bool dummy; + if (report_pin_name(pin, dummy)) { + if (pin_is_protected(pin)) + SERIAL_ECHOPGM(" (protected)"); + else { + SERIAL_ECHOPGM(" = "); + pinMode(pin, INPUT_PULLUP); + SERIAL_ECHO(digitalRead(pin)); + if (IS_ANALOG(pin)) { + SERIAL_CHAR(' '); SERIAL_CHAR('('); + SERIAL_ECHO(analogRead(pin - analogInputToDigitalPin(0))); + SERIAL_CHAR(')'); + } + } + } + SERIAL_EOL; +} + +bool get_pinMode(int8_t pin) { return *portModeRegister(digitalPinToPort(pin)) & digitalPinToBitMask(pin); } + +// pretty report with PWM info +inline void report_pin_state_extended(int8_t pin, bool ignore) { + + char buffer[30]; // for the sprintf statements + + // report pin number + sprintf(buffer, "PIN:% 3d ", pin); + SERIAL_ECHO(buffer); + + // report pin name + bool analog_pin; + report_pin_name(pin, analog_pin); + + // report pin state + if (pin_is_protected(pin) && !ignore) + SERIAL_ECHOPGM("protected "); + else { + if (analog_pin) { + sprintf(buffer, "Analog in =% 5d", analogRead(pin - analogInputToDigitalPin(0))); + SERIAL_ECHO(buffer); + } + else { + if (!get_pinMode(pin)) { + pinMode(pin, INPUT_PULLUP); // make sure input isn't floating + SERIAL_PROTOCOLPAIR("Input = ", digitalRead_mod(pin)); + } + else if (pwm_status(pin)) { + // do nothing + } + else SERIAL_PROTOCOLPAIR("Output = ", digitalRead_mod(pin)); + } + } + + // report PWM capabilities + pwm_details(pin); + SERIAL_EOL; +} + diff --git a/Marlin/pins_3DRAG.h b/Marlin/pins_3DRAG.h index a3a6169028..9eaf2c9f65 100644 --- a/Marlin/pins_3DRAG.h +++ b/Marlin/pins_3DRAG.h @@ -36,36 +36,47 @@ #define DEFAULT_SOURCE_CODE_URL "http://3dprint.elettronicain.it/" #endif +// +// Heaters / Fans +// +#define RAMPS_D8_PIN 9 +#define RAMPS_D9_PIN 8 +#define MOSFET_D_PIN 12 + #include "pins_RAMPS.h" +// +// Limit Switches +// +#undef Z_MAX_PIN +#define Z_MAX_PIN -1 + +// +// Steppers +// #undef Z_ENABLE_PIN #define Z_ENABLE_PIN 63 -#undef X_MAX_PIN -#undef Y_MAX_PIN -#undef Z_MAX_PIN -#define X_MAX_PIN 2 -#define Y_MAX_PIN 15 -#define Z_MAX_PIN -1 +// +// Heaters / Fans +// +#define HEATER_2_PIN 6 +// +// Misc. Functions +// #undef SDSS -#define SDSS 25//53 +#define SDSS 25 -#undef FAN_PIN -#define FAN_PIN 8 - -#undef HEATER_1_PIN -#undef HEATER_2_PIN -#undef HEATER_BED_PIN -#define HEATER_0_PIN 10 -#define HEATER_1_PIN 12 -#define HEATER_2_PIN 6 - -#define HEATER_BED_PIN 9 // BED +#undef SD_DETECT_PIN +#define SD_DETECT_PIN 53 +// +// LCD / Controller +// #if ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) #undef BEEPER_PIN - #define BEEPER_PIN -1 + #define BEEPER_PIN -1 #undef LCD_PINS_RS #undef LCD_PINS_ENABLE @@ -73,23 +84,23 @@ #undef LCD_PINS_D5 #undef LCD_PINS_D6 #undef LCD_PINS_D7 - #define LCD_PINS_RS 27 - #define LCD_PINS_ENABLE 29 - #define LCD_PINS_D4 37 - #define LCD_PINS_D5 35 - #define LCD_PINS_D6 33 - #define LCD_PINS_D7 31 + #define LCD_PINS_RS 27 + #define LCD_PINS_ENABLE 29 + #define LCD_PINS_D4 37 + #define LCD_PINS_D5 35 + #define LCD_PINS_D6 33 + #define LCD_PINS_D7 31 // Buttons #undef BTN_EN1 #undef BTN_EN2 #undef BTN_ENC - #define BTN_EN1 16 - #define BTN_EN2 17 - #define BTN_ENC 23 + #define BTN_EN1 16 + #define BTN_EN2 17 + #define BTN_ENC 23 #else - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 #endif // ULTRA_LCD && NEWPANEL diff --git a/Marlin/pins_5DPRINT.h b/Marlin/pins_5DPRINT.h index dae7e2034f..f44a56887d 100644 --- a/Marlin/pins_5DPRINT.h +++ b/Marlin/pins_5DPRINT.h @@ -33,47 +33,62 @@ #define DEFAULT_MACHINE_NAME "Makibox" #define BOARD_NAME "5DPrint D8" +#define USBCON 1286 // Disable MarlinSerial etc. #define LARGE_FLASH true +// +// Limit Switches +// +#define X_STOP_PIN 37 +#define Y_STOP_PIN 36 +#define Z_STOP_PIN 39 + +// +// Steppers +// #define X_STEP_PIN 0 #define X_DIR_PIN 1 #define X_ENABLE_PIN 23 -#define X_STOP_PIN 37 #define Y_STEP_PIN 2 #define Y_DIR_PIN 3 #define Y_ENABLE_PIN 19 -#define Y_STOP_PIN 36 #define Z_STEP_PIN 4 #define Z_DIR_PIN 5 #define Z_ENABLE_PIN 18 -#define Z_STOP_PIN 39 #define E0_STEP_PIN 6 #define E0_DIR_PIN 7 #define E0_ENABLE_PIN 17 -#define HEATER_0_PIN 21 // Extruder -#define HEATER_BED_PIN 20 // Bed +// Microstepping pins - Mapping not from fastio.h (?) +#define X_MS1_PIN 25 +#define X_MS2_PIN 26 +#define Y_MS1_PIN 9 +#define Y_MS2_PIN 8 +#define Z_MS1_PIN 7 +#define Z_MS2_PIN 6 +#define E0_MS1_PIN 5 +#define E0_MS2_PIN 4 + +// +// Temperature Sensors +// +#define TEMP_0_PIN 1 // Analog Input +#define TEMP_BED_PIN 0 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 21 +#define HEATER_BED_PIN 20 + // You may need to change FAN_PIN to 16 because Marlin isn't using fastio.h // for the fan and Teensyduino uses a different pin mapping. -#define FAN_PIN 16 // Fan +#define FAN_PIN 16 -#define TEMP_0_PIN 1 // Extruder / Analog pin numbering -#define TEMP_BED_PIN 0 // Bed / Analog pin numbering - -// The SDSS pin uses a different pin mapping from file fastio.h +// +// Misc. Functions +// #define SDSS 20 - -// Microstepping pins -// Note that the pin mapping is not from fastio.h -// See Sd2PinMap.h for the pin configurations ??? -#define X_MS1_PIN 25 -#define X_MS2_PIN 26 -#define Y_MS1_PIN 9 -#define Y_MS2_PIN 8 -#define Z_MS1_PIN 7 -#define Z_MS2_PIN 6 -#define E0_MS1_PIN 5 -#define E0_MS2_PIN 4 diff --git a/Marlin/pins_99.h b/Marlin/pins_99.h index 6b7d1e8911..ba86bf58b6 100644 --- a/Marlin/pins_99.h +++ b/Marlin/pins_99.h @@ -23,31 +23,49 @@ /** * Board 99 pin assignments */ + #define BOARD_NAME "99 Unknown" - + +// +// Limit Switches +// +#define X_STOP_PIN 16 +#define Y_STOP_PIN 67 +#define Z_STOP_PIN 59 + +// +// Steppers +// #define X_STEP_PIN 2 #define X_DIR_PIN 3 -#define X_ENABLE_PIN -1 -#define X_STOP_PIN 16 +#define X_ENABLE_PIN -1 #define Y_STEP_PIN 5 #define Y_DIR_PIN 6 #define Y_ENABLE_PIN -1 -#define Y_STOP_PIN 67 -#define Z_STEP_PIN 62 -#define Z_DIR_PIN 63 +#define Z_STEP_PIN 62 +#define Z_DIR_PIN 63 #define Z_ENABLE_PIN -1 -#define Z_STOP_PIN 59 -#define E0_STEP_PIN 65 -#define E0_DIR_PIN 66 +#define E0_STEP_PIN 65 +#define E0_DIR_PIN 66 #define E0_ENABLE_PIN -1 +// +// Temperature Sensors +// +#define TEMP_0_PIN 6 // Analog Input +#define TEMP_BED_PIN 10 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 13 +#define HEATER_BED_PIN 4 + +// +// Misc. Functions +// #define SDSS 53 #define PS_ON_PIN 9 - -#define HEATER_0_PIN 13 -#define TEMP_0_PIN 6 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! -#define HEATER_BED_PIN 4 -#define TEMP_BED_PIN 10 diff --git a/Marlin/pins_A4JP.h b/Marlin/pins_A4JP.h index 990abc3092..bc0fc84d11 100644 --- a/Marlin/pins_A4JP.h +++ b/Marlin/pins_A4JP.h @@ -30,112 +30,132 @@ #define BOARD_NAME "AJ4P" -// Servo support -#define SERVO0_PIN 22 // Motor header MX1 -#define SERVO1_PIN 23 // Motor header MX2 -#define SERVO2_PIN 24 // Motor header MX3 -#define SERVO3_PIN 5 // PWM header pin 5 - -#if ENABLED(Z_PROBE_SLED) - #define SLED_PIN -1 -#endif - -//Fan_2 2 - -/***************** -#if ENABLED(ULTRA_LCD) - - #define KILL_PIN -1 //was 80 Glen maybe a mistake - -#endif // ULTRA_LCD */ - -#if ENABLED(VIKI2) || ENABLED(miniVIKI) - #define BEEPER_PIN 44 - // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 70 - #define DOGLCD_CS 71 - #define LCD_SCREEN_ROT_180 - - #define SD_DETECT_PIN -1 // Pin 72 if using easy adapter board - - #if ENABLED(TEMP_STAT_LEDS) - #define STAT_LED_RED 22 - #define STAT_LED_BLUE 32 - #endif -#endif // VIKI2/miniVIKI - -#define FILWIDTH_PIN 3 // ANALOG NUMBERING +#define LARGE_FLASH true /************************************************ * Rambo pin assignments old ************************************************/ -#define LARGE_FLASH true -#define X_STEP_PIN 37 -#define X_DIR_PIN 48 -#define X_MIN_PIN 12 -#define X_MAX_PIN 24 -#define X_ENABLE_PIN 29 -#define X_MS1_PIN 40 -#define X_MS2_PIN 41 -#define Y_STEP_PIN 36 -#define Y_DIR_PIN 49 -#define Y_MIN_PIN 11 -#define Y_MAX_PIN 23 -#define Y_ENABLE_PIN 28 -#define Y_MS1_PIN 69 -#define Y_MS2_PIN 39 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 47 -#define Z_MIN_PIN 10 -#define Z_MAX_PIN 30 -#define Z_ENABLE_PIN 27 -#define Z_MS1_PIN 68 -#define Z_MS2_PIN 67 +// +// Servos +// +#define SERVO0_PIN 22 // Motor header MX1 +#define SERVO1_PIN 23 // Motor header MX2 +#define SERVO2_PIN 24 // Motor header MX3 +#define SERVO3_PIN 5 // PWM header pin 5 -#define HEATER_BED_PIN 3 -#define TEMP_BED_PIN 7 //2014/02/04 0:T0 / 1:T1 / 2:T2 / 7:T3 -#define HEATER_0_PIN 9 -#define TEMP_0_PIN 0 -#define HEATER_1_PIN 7 +// +// Limit Switches +// +#define X_MIN_PIN 12 +#define X_MAX_PIN 24 +#define Y_MIN_PIN 11 +#define Y_MAX_PIN 23 +#define Z_MIN_PIN 10 +#define Z_MAX_PIN 30 -#define E0_STEP_PIN 34 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 26 -#define E0_MS1_PIN 65 -#define E0_MS2_PIN 66 -#define E1_STEP_PIN 33 -#define E1_DIR_PIN 42 -#define E1_ENABLE_PIN 25 -#define E1_MS1_PIN 63 -#define E1_MS2_PIN 64 +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 30 +#endif -#define DIGIPOTSS_PIN 38 +#define SLED_PIN -1 + +// +// Steppers +// +#define X_STEP_PIN 37 +#define X_DIR_PIN 48 +#define X_ENABLE_PIN 29 + +#define Y_STEP_PIN 36 +#define Y_DIR_PIN 49 +#define Y_ENABLE_PIN 28 + +#define Z_STEP_PIN 35 +#define Z_DIR_PIN 47 +#define Z_ENABLE_PIN 27 + +#define E0_STEP_PIN 34 +#define E0_DIR_PIN 43 +#define E0_ENABLE_PIN 26 + +#define E1_STEP_PIN 33 +#define E1_DIR_PIN 42 +#define E1_ENABLE_PIN 25 + +// Microstepping pins - Mapping not from fastio.h (?) +#define X_MS1_PIN 40 +#define X_MS2_PIN 41 +#define Y_MS1_PIN 69 +#define Y_MS2_PIN 39 +#define Z_MS1_PIN 68 +#define Z_MS2_PIN 67 +#define E0_MS1_PIN 65 +#define E0_MS2_PIN 66 +#define E1_MS1_PIN 63 +#define E1_MS2_PIN 64 + +#define DIGIPOTSS_PIN 38 #define DIGIPOT_CHANNELS {4,5,3,0,1} // X Y Z E0 E1 digipot channels to stepper driver mapping -#define SDSS 53 -#define LED_PIN 13 -#define FAN_PIN 8 -#define PS_ON_PIN 4 -#define FAN_0_PIN 6 //Glen -#define FAN_1_PIN 2 //Glen +// +// Temperature Sensors +// +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_BED_PIN 7 // Analog Input -// 2015/12/23 +// +// Heaters / Fans +// +#define HEATER_0_PIN 9 +#define HEATER_1_PIN 7 +#define HEATER_BED_PIN 3 -#define LCD_PINS_RS 70 //ext2_5 -#define LCD_PINS_ENABLE 71 //ext2_7 -#define LCD_PINS_D4 72 ///////Ext2 9 ? -#define LCD_PINS_D5 73 ///////Ext2 11 ? -#define LCD_PINS_D6 74 //ext2_13 -#define LCD_PINS_D7 75 ///////Ext2 15 ? -#define BEEPER_PIN -1 +#define FAN_PIN 8 +#define FAN1_PIN 6 +#define FAN2_PIN 2 -#define BTN_HOME 80 //ext_16 -#define BTN_CENTER 81 //ext_14 -#define BTN_ENC BTN_CENTER -#define BTN_RIGHT 82 //ext_12 -#define BTN_LEFT 83 //ext_10 -#define BTN_UP 84 //ext2_8 -#define BTN_DOWN 85 //ext2_6 +// +// Misc. Functions +// +#define SDSS 53 +#define LED_PIN 13 +#define PS_ON_PIN 4 +#define FILWIDTH_PIN 3 // Analog Input -#define HOME_PIN BTN_HOME +// +// LCD / Controller +// +#define LCD_PINS_RS 70 // Ext2_5 +#define LCD_PINS_ENABLE 71 // Ext2_7 +#define LCD_PINS_D4 72 // Ext2_9 ? +#define LCD_PINS_D5 73 // Ext2_11 ? +#define LCD_PINS_D6 74 // Ext2_13 +#define LCD_PINS_D7 75 // Ext2_15 ? +#define BEEPER_PIN -1 + +#define BTN_HOME 80 // Ext_16 +#define BTN_CENTER 81 // Ext_14 +#define BTN_ENC BTN_CENTER +#define BTN_RIGHT 82 // Ext_12 +#define BTN_LEFT 83 // Ext_10 +#define BTN_UP 84 // Ext2_8 +#define BTN_DOWN 85 // Ext2_6 + +#define HOME_PIN BTN_HOME + +#if ENABLED(VIKI2) || ENABLED(miniVIKI) + #define BEEPER_PIN 44 + // Pins for DOGM SPI LCD Support + #define DOGLCD_A0 70 + #define DOGLCD_CS 71 + #define LCD_SCREEN_ROT_180 + + #define SD_DETECT_PIN -1 // Pin 72 if using easy adapter board + + #define STAT_LED_RED_PIN 22 + #define STAT_LED_BLUE_PIN 32 +#endif // VIKI2/miniVIKI diff --git a/Marlin/pins_AZTEEG_X3.h b/Marlin/pins_AZTEEG_X3.h index b33818ee79..26f274e6fe 100644 --- a/Marlin/pins_AZTEEG_X3.h +++ b/Marlin/pins_AZTEEG_X3.h @@ -32,6 +32,17 @@ #include "pins_RAMPS_13.h" +// +// Servos +// +#undef SERVO0_PIN +#undef SERVO1_PIN +#define SERVO0_PIN 44 // SERVO1 port +#define SERVO1_PIN 55 // SERVO2 port + +// +// LCD / Controller +// #if ENABLED(VIKI2) || ENABLED(miniVIKI) #undef DOGLCD_A0 @@ -41,16 +52,14 @@ #define DOGLCD_CS 32 #define BTN_ENC 12 - #if ENABLED(TEMP_STAT_LEDS) - #undef STAT_LED_RED - #undef STAT_LED_BLUE - #define STAT_LED_RED 64 - #define STAT_LED_BLUE 63 - #endif + #undef STAT_LED_RED_PIN + #undef STAT_LED_BLUE_PIN + #define STAT_LED_RED_PIN 64 + #define STAT_LED_BLUE_PIN 63 -#elif ENABLED(TEMP_STAT_LEDS) +#else - #define STAT_LED_RED 6 - #define STAT_LED_BLUE 11 + #define STAT_LED_RED_PIN 6 + #define STAT_LED_BLUE_PIN 11 #endif diff --git a/Marlin/pins_AZTEEG_X3_PRO.h b/Marlin/pins_AZTEEG_X3_PRO.h index f4114c568d..06c2934104 100644 --- a/Marlin/pins_AZTEEG_X3_PRO.h +++ b/Marlin/pins_AZTEEG_X3_PRO.h @@ -28,21 +28,20 @@ #include "pins_RAMPS.h" -#undef FAN_PIN -#define FAN_PIN 6 //Part Cooling System - -#undef BEEPER_PIN -#define BEEPER_PIN 33 -#define CONTROLLERFAN_PIN 4 //Pin used for the fan to cool motherboard (-1 to disable) -//Fans/Water Pump to cool the hotend cool side. -#define EXTRUDER_0_AUTO_FAN_PIN 5 -#define EXTRUDER_1_AUTO_FAN_PIN 5 -#define EXTRUDER_2_AUTO_FAN_PIN 5 -#define EXTRUDER_3_AUTO_FAN_PIN 5 // -//This section is to swap the MIN and MAX pins because the X3 Pro comes with only -//MIN endstops soldered onto the board. Delta code wants the homing endstops to be -//the MAX so I swapped them here. +// Servos +// +// Tested this pin with bed leveling on a Delta with 1 servo. +// Physical wire attachment on EXT1: GND, 5V, D47. +// +#undef SERVO0_PIN +#define SERVO0_PIN 47 + +// +// Limit Switches +// +// Swap the MIN and MAX endstop pins because the X3 Pro comes with only +// MIN endstop pin headers soldered onto the board. // #if ENABLED(DELTA) #undef X_MIN_PIN @@ -60,10 +59,16 @@ #define Z_MAX_PIN 18 #endif +// +// Z Probe (when not Z_MIN_PIN) +// #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 19 + #define Z_MIN_PROBE_PIN 18 #endif +// +// Steppers +// #define E2_STEP_PIN 23 #define E2_DIR_PIN 25 #define E2_ENABLE_PIN 40 @@ -76,10 +81,18 @@ #define E4_DIR_PIN 37 #define E4_ENABLE_PIN 42 -#undef HEATER_1_PIN -#undef HEATER_2_PIN -#undef HEATER_3_PIN -#define HEATER_1_PIN 9 +// +// Temperature Sensors +// +#define TEMP_2_PIN 12 // Analog Input +#define TEMP_3_PIN 11 // Analog Input +#define TEMP_4_PIN 10 // Analog Input +#define TC1 4 // Analog Input (Thermo couple on Azteeg X3Pro) +#define TC2 5 // Analog Input (Thermo couple on Azteeg X3Pro) + +// +// Heaters / Fans +// #define HEATER_2_PIN 16 #define HEATER_3_PIN 17 #define HEATER_4_PIN 4 @@ -87,26 +100,27 @@ #define HEATER_6_PIN 6 #define HEATER_7_PIN 11 -#undef TEMP_2_PIN -#undef TEMP_3_PIN -#define TEMP_2_PIN 12 // ANALOG NUMBERING -#define TEMP_3_PIN 11 // ANALOG NUMBERING -#define TEMP_4_PIN 10 // ANALOG NUMBERING -#define TC1 4 // ANALOG NUMBERING Thermo couple on Azteeg X3Pro -#define TC2 5 // ANALOG NUMBERING Thermo couple on Azteeg X3Pro +#undef FAN_PIN +#define FAN_PIN 6 // Part Cooling System + +#define CONTROLLERFAN_PIN 4 // Pin used for the fan to cool motherboard (-1 to disable) + +// Fans/Water Pump to cool the hotend cool side. +#define ORIG_E0_AUTO_FAN_PIN 5 +#define ORIG_E1_AUTO_FAN_PIN 5 +#define ORIG_E2_AUTO_FAN_PIN 5 +#define ORIG_E3_AUTO_FAN_PIN 5 // -// These Servo pins are for when they are defined. Tested for usage with bed leveling -// on a Delta with 1 servo. Running through the Z servo endstop in code. -// Physical wire attachment was done on EXT1 on the GND, 5V, and D47 pins. +// LCD / Controller // -#undef SERVO0_PIN -#define SERVO0_PIN 47 +#undef BEEPER_PIN +#define BEEPER_PIN 33 #if ENABLED(VIKI2) || ENABLED(miniVIKI) #undef SD_DETECT_PIN - #define SD_DETECT_PIN 49 // For easy adapter board -#elif ENABLED(TEMP_STAT_LEDS) - #define STAT_LED_RED 32 - #define STAT_LED_BLUE 35 + #define SD_DETECT_PIN 49 // For easy adapter board +#else + #define STAT_LED_RED_PIN 32 + #define STAT_LED_BLUE_PIN 35 #endif diff --git a/Marlin/pins_BAM_DICE_DUE.h b/Marlin/pins_BAM_DICE_DUE.h index 0c5914f2b9..488861d5c9 100644 --- a/Marlin/pins_BAM_DICE_DUE.h +++ b/Marlin/pins_BAM_DICE_DUE.h @@ -32,7 +32,10 @@ #include "pins_RAMPS.h" +// +// Temperature Sensors +// #undef TEMP_0_PIN #undef TEMP_1_PIN -#define TEMP_0_PIN 9 // ANALOG NUMBERING -#define TEMP_1_PIN 11 // ANALOG NUMBERING +#define TEMP_0_PIN 9 // Analog Input +#define TEMP_1_PIN 11 // Analog Input diff --git a/Marlin/pins_BQ_ZUM_MEGA_3D.h b/Marlin/pins_BQ_ZUM_MEGA_3D.h index c5509d4e5f..dff48a4521 100644 --- a/Marlin/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/pins_BQ_ZUM_MEGA_3D.h @@ -30,40 +30,56 @@ #define BOARD_NAME "ZUM Mega 3D" +// +// Heaters / Fans +// +#define RAMPS_D8_PIN 10 +#define RAMPS_D9_PIN 12 +#define RAMPS_D10_PIN 9 +#define MOSFET_D_PIN 7 + +// +// Auto fans +// +#define ORIG_E0_AUTO_FAN_PIN 11 +#define ORIG_E1_AUTO_FAN_PIN 6 +#define ORIG_E2_AUTO_FAN_PIN 6 +#define ORIG_E3_AUTO_FAN_PIN 6 + #include "pins_RAMPS_13.h" +// +// Limit Switches +// #undef X_MAX_PIN -#define X_MAX_PIN 79 // 2 +#define X_MAX_PIN 79 // 2 + +// +// Z Probe (when not Z_MIN_PIN) +// +#undef Z_MIN_PROBE_PIN +#define Z_MIN_PROBE_PIN 19 // IND_S_5V #undef Z_ENABLE_PIN #define Z_ENABLE_PIN 77 // 62 -#undef FAN_PIN -#define FAN_PIN 12 // 4 - -#undef HEATER_0_PIN -#define HEATER_0_PIN 9 // 10 - -#undef HEATER_1_PIN -#define HEATER_1_PIN 10 // 9 - -#undef TEMP_1_PIN -#define TEMP_1_PIN 14 // 15 - -#undef TEMP_BED_PIN -#define TEMP_BED_PIN 15 // 14 - +// +// Steppers +// #define DIGIPOTSS_PIN 22 #define DIGIPOT_CHANNELS { 4, 5, 3, 0, 1 } -#define FAN1_PIN 7 +// +// Temperature Sensors +// +#undef TEMP_1_PIN +#define TEMP_1_PIN 14 // Analog Input (15) +#undef TEMP_BED_PIN +#define TEMP_BED_PIN 15 // Analog Input (14) + +// +// Misc. Functions +// #undef PS_ON_PIN // 12 #define PS_ON_PIN 81 // External Power Supply - -#if ENABLED(AUTO_BED_LEVELING_FEATURE) - #undef Z_MIN_PIN - #undef Z_MAX_PIN - #define Z_MIN_PIN 19 // IND_S_5V - #define Z_MAX_PIN 18 // Z-MIN Label -#endif diff --git a/Marlin/pins_BRAINWAVE.h b/Marlin/pins_BRAINWAVE.h index 9dfeb3ab1f..ba9d04099c 100644 --- a/Marlin/pins_BRAINWAVE.h +++ b/Marlin/pins_BRAINWAVE.h @@ -33,22 +33,31 @@ #define BOARD_NAME "Brainwave" +#define USBCON 646 // Disable MarlinSerial etc. + +// +// Limit Switches +// +#define X_STOP_PIN 7 +#define Y_STOP_PIN 6 +#define Z_STOP_PIN 5 + +// +// Steppers +// #define X_STEP_PIN 27 #define X_DIR_PIN 29 #define X_ENABLE_PIN 28 -#define X_STOP_PIN 7 #define X_ATT_PIN 26 #define Y_STEP_PIN 31 #define Y_DIR_PIN 33 #define Y_ENABLE_PIN 32 -#define Y_STOP_PIN 6 #define Y_ATT_PIN 30 #define Z_STEP_PIN 17 #define Z_DIR_PIN 19 #define Z_ENABLE_PIN 18 -#define Z_STOP_PIN 5 #define Z_ATT_PIN 16 #define E0_STEP_PIN 21 @@ -56,11 +65,21 @@ #define E0_ENABLE_PIN 22 #define E0_ATT_PIN 20 +// +// Temperature Sensors +// +#define TEMP_0_PIN 7 // Analog Input +#define TEMP_BED_PIN 6 // Analog Input + +// +// Heaters / Fans +// #define HEATER_0_PIN 4 // Extruder #define HEATER_BED_PIN 38 // Bed + #define FAN_PIN 3 // Fan -#define TEMP_0_PIN 7 // Extruder / Analog pin numbering -#define TEMP_BED_PIN 6 // Bed / Analog pin numbering - +// +// Misc. Functions +// #define LED_PIN 39 diff --git a/Marlin/pins_BRAINWAVE_PRO.h b/Marlin/pins_BRAINWAVE_PRO.h index cba0d46944..b353581f0a 100644 --- a/Marlin/pins_BRAINWAVE_PRO.h +++ b/Marlin/pins_BRAINWAVE_PRO.h @@ -33,21 +33,32 @@ #include "fastio.h" -#ifndef AT90USBxx_TEENSYPP_ASSIGNMENTS // use Teensyduino Teensy++2.0 pin assignments instead of Marlin alphabetical. +#if DISABLED(AT90USBxx_TEENSYPP_ASSIGNMENTS) // use Teensyduino Teensy++2.0 pin assignments instead of Marlin alphabetical. #error "Uncomment #define AT90USBxx_TEENSYPP_ASSIGNMENTS in fastio.h for this config" #endif #define BOARD_NAME "Brainwave Pro" +#define USBCON 1286 // Disable MarlinSerial etc. #define LARGE_FLASH true +// +// Limit Switches +// #define X_STOP_PIN 47 #define Y_STOP_PIN 18 #define Z_MAX_PIN 36 + +// +// Z Probe (when not Z_MIN_PIN) +// #ifndef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN 17 #endif +// +// Steppers +// #define X_STEP_PIN 33 #define X_DIR_PIN 32 #define X_ENABLE_PIN 11 @@ -64,14 +75,23 @@ #define E0_DIR_PIN 34 #define E0_ENABLE_PIN 13 +// +// Temperature Sensors +// +#define TEMP_0_PIN 2 // Analog Input +#define TEMP_1_PIN 1 // Analog Input +#define TEMP_BED_PIN 0 // Analog Input + +// +// Heaters / Fans +// #define HEATER_0_PIN 15 #define HEATER_BED_PIN 14 // Bed #define FAN_PIN 16 // Fan, PWM -#define TEMP_0_PIN 2 // Extruder / Analog pin numbering -#define TEMP_1_PIN 1 // Spare / Analog pin numbering -#define TEMP_BED_PIN 0 // Bed / Analog pin numbering - +// +// Misc. Functions +// #define SDSS 20 -#define LED_PIN 19 #define SD_DETECT_PIN 12 +#define LED_PIN 19 diff --git a/Marlin/pins_CHEAPTRONIC.h b/Marlin/pins_CHEAPTRONIC.h index 2fbb4e8356..d1da32cd82 100644 --- a/Marlin/pins_CHEAPTRONIC.h +++ b/Marlin/pins_CHEAPTRONIC.h @@ -31,57 +31,62 @@ #define BOARD_NAME "Cheaptronic v1.0" #define LARGE_FLASH true -// X motor stepper -#define X_STEP_PIN 14 -#define X_DIR_PIN 15 -#define X_ENABLE_PIN 24 +// +// Limit Switches +// +#define X_STOP_PIN 3 +#define Y_STOP_PIN 2 +#define Z_STOP_PIN 5 -// Y motor stepper -#define Y_STEP_PIN 35 -#define Y_DIR_PIN 36 -#define Y_ENABLE_PIN 31 +// +// Steppers +// +#define X_STEP_PIN 14 +#define X_DIR_PIN 15 +#define X_ENABLE_PIN 24 -// Z motor stepper -#define Z_STEP_PIN 40 -#define Z_DIR_PIN 41 -#define Z_ENABLE_PIN 37 +#define Y_STEP_PIN 35 +#define Y_DIR_PIN 36 +#define Y_ENABLE_PIN 31 -// XYZ endstops -#define X_STOP_PIN 3 -#define Y_STOP_PIN 2 -#define Z_STOP_PIN 5 +#define Z_STEP_PIN 40 +#define Z_DIR_PIN 41 +#define Z_ENABLE_PIN 37 -// Extruder 0 stepper -#define E0_STEP_PIN 26 -#define E0_DIR_PIN 28 -#define E0_ENABLE_PIN 25 +#define E0_STEP_PIN 26 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 25 -// Extruder 1 stepper -#define E1_STEP_PIN 33 -#define E1_DIR_PIN 34 -#define E1_ENABLE_PIN 30 - - -#define HEATER_0_PIN 19 // EXTRUDER 1 -#define HEATER_1_PIN 23 // EXTRUDER 2 -#define HEATER_BED_PIN 22 +#define E1_STEP_PIN 33 +#define E1_DIR_PIN 34 +#define E1_ENABLE_PIN 30 +// // Temperature sensors -#define TEMP_0_PIN 15 -#define TEMP_1_PIN 14 -#define TEMP_BED_PIN 13 +// +#define TEMP_0_PIN 15 // Analog Input +#define TEMP_1_PIN 14 // Analog Input +#define TEMP_BED_PIN 13 // Analog Input +// +// Heaters / Fans +// +#define HEATER_0_PIN 19 // EXTRUDER 1 +#define HEATER_1_PIN 23 // EXTRUDER 2 +#define HEATER_BED_PIN 22 + +// +// LCD / Controller +// // Cheaptronic v1.0 doesn't support LCD -#define LCD_PINS_RS -1 -#define LCD_PINS_ENABLE -1 -#define LCD_PINS_D4 -1 -#define LCD_PINS_D5 -1 -#define LCD_PINS_D6 -1 -#define LCD_PINS_D7 -1 +#define LCD_PINS_RS -1 +#define LCD_PINS_ENABLE -1 +#define LCD_PINS_D4 -1 +#define LCD_PINS_D5 -1 +#define LCD_PINS_D6 -1 +#define LCD_PINS_D7 -1 // Cheaptronic v1.0 doesn't support keypad -#define BTN_EN1 -1 -#define BTN_EN2 -1 -#define BTN_ENC -1 - -// Cheaptronic v1.0 doesn't use this +#define BTN_EN1 -1 +#define BTN_EN2 -1 +#define BTN_ENC -1 diff --git a/Marlin/pins_CNCONTROLS_11.h b/Marlin/pins_CNCONTROLS_11.h index 1de35a2c17..fdf6c317e5 100644 --- a/Marlin/pins_CNCONTROLS_11.h +++ b/Marlin/pins_CNCONTROLS_11.h @@ -6,54 +6,79 @@ #error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu. #endif -#define BOARD_NAME "CN Controls V11" +#define BOARD_NAME "CN Controls V11" //#define LARGE_FLASH true -#define X_ENABLE_PIN 35 -#define X_STEP_PIN 34 -#define X_DIR_PIN 36 -#define X_MIN_PIN 43 -#define X_MAX_PIN -1 +// +// Limit Switches +// +#define X_STOP_PIN 43 +#define Y_STOP_PIN 45 +#define Z_STOP_PIN 42 -#define Y_ENABLE_PIN 38 -#define Y_STEP_PIN 37 -#define Y_DIR_PIN 39 -#define Y_MIN_PIN 45 -#define Y_MAX_PIN -1 +// +// Steppers +// +#define X_STEP_PIN 34 +#define X_DIR_PIN 36 +#define X_ENABLE_PIN 35 -#define Z_ENABLE_PIN 41 -#define Z_STEP_PIN 40 -#define Z_DIR_PIN 48 -#define Z_MIN_PIN 42 -#define Z_MAX_PIN -1 +#define Y_STEP_PIN 37 +#define Y_DIR_PIN 39 +#define Y_ENABLE_PIN 38 -#define E0_ENABLE_PIN 3 -#define E0_STEP_PIN 29 -#define E0_DIR_PIN 28 -#define HEATER_0_PIN 5 -#define TEMP_0_PIN 0 // ANALOG INPUT !! +#define Z_STEP_PIN 40 +#define Z_DIR_PIN 48 +#define Z_ENABLE_PIN 41 -#define E1_ENABLE_PIN 60 -#define E1_STEP_PIN 61 -#define E1_DIR_PIN 62 -#define HEATER_1_PIN 58 -#define TEMP_1_PIN 3 // 3 for tool2 -> 2 for chambertemp +#define E0_STEP_PIN 29 +#define E0_DIR_PIN 28 +#define E0_ENABLE_PIN 3 -#define E2_ENABLE_PIN 16 -#define E2_STEP_PIN 15 -#define E2_DIR_PIN 14 -#define HEATER_2_PIN 64 -#define TEMP_2_PIN 2 // 9 for tool3 -> 2 for chambertemp +#define E1_STEP_PIN 61 +#define E1_DIR_PIN 62 +#define E1_ENABLE_PIN 60 -#define E3_ENABLE_PIN 47 -#define E3_STEP_PIN 44 -#define E3_DIR_PIN 49 -#define HEATER_3_PIN 46 -#define TEMP_3_PIN 11 // 11 for tool4 -> 2 for chambertemp +#define E2_STEP_PIN 15 +#define E2_DIR_PIN 14 +#define E2_ENABLE_PIN 16 -#define HEATER_BED_PIN 2 -#define TEMP_BED_PIN 1 // ANALOG INPUT !! +#define E3_STEP_PIN 44 +#define E3_DIR_PIN 49 +#define E3_ENABLE_PIN 47 + +// +// Temperature Sensors +// +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 3 // Analog Input. 3 for tool2 -> 2 for chambertemp +#define TEMP_2_PIN 2 // Analog Input. 9 for tool3 -> 2 for chambertemp +#define TEMP_3_PIN 11 // Analog Input. 11 for tool4 -> 2 for chambertemp +#define TEMP_BED_PIN 1 // Analog Input +//#define TEMP_CHAMBER_PIN 2 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 5 +#define HEATER_1_PIN 58 +#define HEATER_2_PIN 64 +#define HEATER_3_PIN 46 +#define HEATER_BED_PIN 2 + +//#define FAN_PIN 7 // common PWM pin for all tools + +#define ORIG_E0_AUTO_FAN_PIN 7 +#define ORIG_E1_AUTO_FAN_PIN 7 +#define ORIG_E2_AUTO_FAN_PIN 7 +#define ORIG_E3_AUTO_FAN_PIN 7 + +// +// Misc. Functions +// +#define SDSS 53 +#define SD_DETECT_PIN 13 // Tools @@ -65,37 +90,33 @@ // Common I/O -//#define TEMP_CHAMBER_PIN 2 // ANALOG INPUT !! //#define FIL_RUNOUT_PIN -1 //#define PWM_1_PIN 11 //#define PWM_2_PIN 10 //#define SPARE_IO 12 -//#define FAN_PIN 7 // common PWM pin for all tools -// User interface -#define BEEPER_PIN 6 +// +// LCD / Controller +// +#define BEEPER_PIN 6 // Pins for DOGM SPI LCD Support -#define DOGLCD_A0 26 -#define DOGLCD_CS 24 -#define DOGLCD_MOSI -1 -#define DOGLCD_SCK -1 +#define DOGLCD_A0 26 +#define DOGLCD_CS 24 +#define DOGLCD_MOSI -1 +#define DOGLCD_SCK -1 -// The encoder and click button -#define BTN_EN1 23 -#define BTN_EN2 25 -#define BTN_ENC 27 +#define BTN_EN1 23 +#define BTN_EN2 25 +#define BTN_ENC 27 // Hardware buttons for manual movement of XYZ -#define SHIFT_OUT 19 -#define SHIFT_LD 18 -#define SHIFT_CLK 17 +#define SHIFT_OUT 19 +#define SHIFT_LD 18 +#define SHIFT_CLK 17 -//#define UI1 31 -//#define UI2 22 +//#define UI1 31 +//#define UI2 22 -// Other -#define SDSS 53 -#define SD_DETECT_PIN 13 -#define STAT_LED_BLUE -1 -#define STAT_LED_RED 31 +#define STAT_LED_BLUE_PIN -1 +#define STAT_LED_RED_PIN 31 diff --git a/Marlin/pins_CNCONTROLS_12.h b/Marlin/pins_CNCONTROLS_12.h index cb338346d9..809d1a6db2 100644 --- a/Marlin/pins_CNCONTROLS_12.h +++ b/Marlin/pins_CNCONTROLS_12.h @@ -10,96 +10,118 @@ //#define LARGE_FLASH true -#define X_ENABLE_PIN 26 -#define X_STEP_PIN 25 -#define X_DIR_PIN 27 -#define X_MIN_PIN 19 -#define X_MAX_PIN -1 +// +// Limit Switches +// +#define X_STOP_PIN 19 +#define Y_STOP_PIN 22 +#define Z_STOP_PIN 23 -#define Y_ENABLE_PIN 29 -#define Y_STEP_PIN 28 -#define Y_DIR_PIN 30 -#define Y_MIN_PIN 22 -#define Y_MAX_PIN -1 +// +// Steppers +// +#define X_STEP_PIN 25 +#define X_DIR_PIN 27 +#define X_ENABLE_PIN 26 -#define Z_ENABLE_PIN 32 -#define Z_STEP_PIN 31 -#define Z_DIR_PIN 33 -#define Z_MIN_PIN 23 -#define Z_MAX_PIN -1 +#define Y_STEP_PIN 28 +#define Y_DIR_PIN 30 +#define Y_ENABLE_PIN 29 -#define E0_ENABLE_PIN 58 -#define E0_STEP_PIN 57 -#define E0_DIR_PIN 55 -#define HEATER_0_PIN 11 -#define TEMP_0_PIN 0 // ANALOG INPUT !! +#define Z_STEP_PIN 31 +#define Z_DIR_PIN 33 +#define Z_ENABLE_PIN 32 -#define E1_ENABLE_PIN 60 -#define E1_STEP_PIN 61 -#define E1_DIR_PIN 62 -#define HEATER_1_PIN 9 -#define TEMP_1_PIN 9 // 9 for tool2 -> 13 for chambertemp +#define E0_STEP_PIN 57 +#define E0_DIR_PIN 55 +#define E0_ENABLE_PIN 58 -#define E2_ENABLE_PIN 44 -#define E2_STEP_PIN 46 -#define E2_DIR_PIN 66 -#define HEATER_2_PIN 6 -#define TEMP_2_PIN 13 // 10 for tool3 -> 13 for chambertemp +#define E1_STEP_PIN 61 +#define E1_DIR_PIN 62 +#define E1_ENABLE_PIN 60 -#define E3_ENABLE_PIN 47 -#define E3_STEP_PIN 45 -#define E3_DIR_PIN 69 -#define HEATER_3_PIN 3 -#define TEMP_3_PIN 11 // 11 for tool4 -> 13 for chambertemp +#define E2_STEP_PIN 46 +#define E2_DIR_PIN 66 +#define E2_ENABLE_PIN 44 -#define HEATER_BED_PIN 24 -#define TEMP_BED_PIN 14 // ANALOG INPUT !! +#define E3_STEP_PIN 45 +#define E3_DIR_PIN 69 +#define E3_ENABLE_PIN 47 + +// +// Temperature Sensors +// +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 9 // Analog Input. 9 for tool2 -> 13 for chambertemp +#define TEMP_2_PIN 13 // Analog Input. 10 for tool3 -> 13 for chambertemp +#define TEMP_3_PIN 11 // Analog Input. 11 for tool4 -> 13 for chambertemp +#define TEMP_BED_PIN 14 // Analog Input +//#define TEMP_CHAMBER_PIN 13 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 11 +#define HEATER_1_PIN 9 +#define HEATER_2_PIN 6 +#define HEATER_3_PIN 3 +#define HEATER_BED_PIN 24 + +#define FAN_PIN 5 // 5 is PWMtool3 -> 7 is common PWM pin for all tools + +#define ORIG_E0_AUTO_FAN_PIN 7 +#define ORIG_E1_AUTO_FAN_PIN 7 +#define ORIG_E2_AUTO_FAN_PIN 7 +#define ORIG_E3_AUTO_FAN_PIN 7 + +// +// Misc. Functions +// +#define SDSS 53 +#define SD_DETECT_PIN 15 // Tools -//#define TOOL_0_PIN 56 -//#define TOOL_0_PWM_PIN 10 // red warning led at dual extruder -//#define TOOL_1_PIN 59 -//#define TOOL_1_PWM_PIN 8 // lights at dual extruder -//#define TOOL_2_PIN 4 -//#define TOOL_2_PWM_PIN 5 -//#define TOOL_3_PIN 14 -//#define TOOL_3_PWM_PIN 2 +//#define TOOL_0_PIN 56 +//#define TOOL_0_PWM_PIN 10 // red warning led at dual extruder +//#define TOOL_1_PIN 59 +//#define TOOL_1_PWM_PIN 8 // lights at dual extruder +//#define TOOL_2_PIN 4 +//#define TOOL_2_PWM_PIN 5 +//#define TOOL_3_PIN 14 +//#define TOOL_3_PWM_PIN 2 // Common I/O -//#define TEMP_CHAMBER_PIN 13 // ANALOG INPUT !! -#define FIL_RUNOUT_PIN 18 -//#define PWM_1_PIN 12 -//#define PWM_2_PIN 13 -//#define SPARE_IO 17 -#define FAN_PIN 5 // 5 is PWMtool3 -> 7 is common PWM pin for all tools +#define FIL_RUNOUT_PIN 18 +//#define PWM_1_PIN 12 +//#define PWM_2_PIN 13 +//#define SPARE_IO 17 -// User interface -#define BEEPER_PIN 16 +// +// LCD / Controller +// +#define BEEPER_PIN 16 // Pins for DOGM SPI LCD Support -#define DOGLCD_A0 39 -#define DOGLCD_CS 35 -#define DOGLCD_MOSI 48 -#define DOGLCD_SCK 49 +#define DOGLCD_A0 39 +#define DOGLCD_CS 35 +#define DOGLCD_MOSI 48 +#define DOGLCD_SCK 49 #define LCD_SCREEN_ROT_180 // The encoder and click button -#define BTN_EN1 36 -#define BTN_EN2 34 -#define BTN_ENC 38 +#define BTN_EN1 36 +#define BTN_EN2 34 +#define BTN_ENC 38 // Hardware buttons for manual movement of XYZ -#define SHIFT_OUT 42 -#define SHIFT_LD 41 -#define SHIFT_CLK 40 +#define SHIFT_OUT 42 +#define SHIFT_LD 41 +#define SHIFT_CLK 40 -//#define UI1 43 -//#define UI2 37 +//#define UI1 43 +//#define UI2 37 -// Other -#define SDSS 53 -#define SD_DETECT_PIN 15 -#define STAT_LED_BLUE -1 -#define STAT_LED_RED 10 // TOOL_0_PWM_PIN +#define STAT_LED_BLUE_PIN -1 +#define STAT_LED_RED_PIN 10 // TOOL_0_PWM_PIN diff --git a/Marlin/pins_ELEFU_3.h b/Marlin/pins_ELEFU_3.h index 2b8e64d8e5..51bd078648 100644 --- a/Marlin/pins_ELEFU_3.h +++ b/Marlin/pins_ELEFU_3.h @@ -28,58 +28,82 @@ #error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu." #endif -#define BOARD_NAME "Elefu Ra v3" +#define BOARD_NAME "Elefu Ra v3" +// +// Limit Switches +// +#define X_MIN_PIN 35 +#define X_MAX_PIN 34 +#define Y_MIN_PIN 33 +#define Y_MAX_PIN 32 +#define Z_MIN_PIN 31 +#define Z_MAX_PIN 30 + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 30 +#endif + +// +// Steppers +// #define X_STEP_PIN 49 #define X_DIR_PIN 13 #define X_ENABLE_PIN 48 -#define X_MIN_PIN 35 -#define X_MAX_PIN 34 #define Y_STEP_PIN 11 #define Y_DIR_PIN 9 #define Y_ENABLE_PIN 12 -#define Y_MIN_PIN 33 -#define Y_MAX_PIN 32 #define Z_STEP_PIN 7 #define Z_DIR_PIN 6 #define Z_ENABLE_PIN 8 -#define Z_MIN_PIN 31 -#define Z_MAX_PIN 30 - -#define E2_STEP_PIN 43 -#define E2_DIR_PIN 47 -#define E2_ENABLE_PIN 42 - -#define E1_STEP_PIN 18 -#define E1_DIR_PIN 19 -#define E1_ENABLE_PIN 38 #define E0_STEP_PIN 40 #define E0_DIR_PIN 41 #define E0_ENABLE_PIN 37 -#define FAN_PIN 16 //5V PWM +#define E1_STEP_PIN 18 +#define E1_DIR_PIN 19 +#define E1_ENABLE_PIN 38 -#define PS_ON_PIN 10 //Set to -1 if using a manual switch on the PWRSW Connector -#define SLEEP_WAKE_PIN 26 //This feature still needs work +#define E2_STEP_PIN 43 +#define E2_DIR_PIN 47 +#define E2_ENABLE_PIN 42 -#define HEATER_0_PIN 45 //12V PWM1 -#define HEATER_1_PIN 46 //12V PWM2 -#define HEATER_2_PIN 17 //12V PWM3 -#define HEATER_BED_PIN 44 //DOUBLE 12V PWM -#define TEMP_0_PIN 3 //ANALOG NUMBERING -#define TEMP_1_PIN 2 //ANALOG NUMBERING -#define TEMP_2_PIN 1 //ANALOG NUMBERING -#define TEMP_BED_PIN 0 //ANALOG NUMBERING +// +// Temperature Sensors +// +#define TEMP_0_PIN 3 // Analog Input +#define TEMP_1_PIN 2 // Analog Input +#define TEMP_2_PIN 1 // Analog Input +#define TEMP_BED_PIN 0 // Analog Input -#define BEEPER_PIN 36 +// +// Heaters / Fans +// +#define HEATER_0_PIN 45 // 12V PWM1 +#define HEATER_1_PIN 46 // 12V PWM2 +#define HEATER_2_PIN 17 // 12V PWM3 +#define HEATER_BED_PIN 44 // DOUBLE 12V PWM -// M240 Triggers a camera by emulating a Canon RC-1 Remote -// Data from: http://www.doc-diy.net/photo/rc-1_hacked/ +#define FAN_PIN 16 // 5V PWM + +// +// Misc. Functions +// +#define PS_ON_PIN 10 // Set to -1 if using a manual switch on the PWRSW Connector +#define SLEEP_WAKE_PIN 26 // This feature still needs work #define PHOTOGRAPH_PIN 29 +// +// LCD / Controller +// +#define BEEPER_PIN 36 + #if ENABLED(RA_CONTROL_PANEL) #define SDSS 53 @@ -92,34 +116,34 @@ #endif // RA_CONTROL_PANEL #if ENABLED(RA_DISCO) - //variables for which pins the TLC5947 is using + // variables for which pins the TLC5947 is using #define TLC_CLOCK_PIN 25 #define TLC_BLANK_PIN 23 #define TLC_XLAT_PIN 22 #define TLC_DATA_PIN 24 - //We also need to define pin to port number mapping for the 2560 to match the pins listed above. If you change the TLC pins, update this as well per the 2560 datasheet! - //This currently only works with the RA Board. - #define TLC_CLOCK_BIT 3 //bit 3 on port A - #define TLC_CLOCK_PORT &PORTA //bit 3 on port A + // We also need to define pin to port number mapping for the 2560 to match the pins listed above. If you change the TLC pins, update this as well per the 2560 datasheet! + // This currently only works with the RA Board. + #define TLC_CLOCK_BIT 3 // bit 3 on port A + #define TLC_CLOCK_PORT &PORTA // bit 3 on port A - #define TLC_BLANK_BIT 1 //bit 1 on port A - #define TLC_BLANK_PORT &PORTA //bit 1 on port A + #define TLC_BLANK_BIT 1 // bit 1 on port A + #define TLC_BLANK_PORT &PORTA // bit 1 on port A - #define TLC_DATA_BIT 2 //bit 2 on port A - #define TLC_DATA_PORT &PORTA //bit 2 on port A + #define TLC_DATA_BIT 2 // bit 2 on port A + #define TLC_DATA_PORT &PORTA // bit 2 on port A - #define TLC_XLAT_BIT 0 //bit 0 on port A - #define TLC_XLAT_PORT &PORTA //bit 0 on port A + #define TLC_XLAT_BIT 0 // bit 0 on port A + #define TLC_XLAT_PORT &PORTA // bit 0 on port A - //change this to match your situation. Lots of TLCs takes up the arduino SRAM very quickly, so be careful - //Leave it at at least 1 if you have enabled RA_LIGHTING - //The number of TLC5947 boards chained together for use with the animation, additional ones will repeat the animation on them, but are not individually addressable and mimic those before them. You can leave the default at 2 even if you only have 1 TLC5947 module. + // change this to match your situation. Lots of TLCs takes up the arduino SRAM very quickly, so be careful + // Leave it at at least 1 if you have enabled RA_LIGHTING + // The number of TLC5947 boards chained together for use with the animation, additional ones will repeat the animation on them, but are not individually addressable and mimic those before them. You can leave the default at 2 even if you only have 1 TLC5947 module. #define NUM_TLCS 2 - //These TRANS_ARRAY values let you change the order the LEDs on the lighting modules will animate for chase functions. - //Modify them according to your specific situation. - //NOTE: the array should be 8 long for every TLC you have. These defaults assume (2) TLCs. + // These TRANS_ARRAY values let you change the order the LEDs on the lighting modules will animate for chase functions. + // Modify them according to your specific situation. + // NOTE: the array should be 8 long for every TLC you have. These defaults assume (2) TLCs. #define TRANS_ARRAY {0, 1, 2, 3, 4, 5, 6, 7, 15, 14, 13, 12, 11, 10, 9, 8} //forwards //#define TRANS_ARRAY {7, 6, 5, 4, 3, 2, 1, 0, 8, 9, 10, 11, 12, 13, 14, 15} //backwards #endif // RA_DISCO diff --git a/Marlin/pins_FELIX2.h b/Marlin/pins_FELIX2.h index 31906b5151..45bf257c42 100644 --- a/Marlin/pins_FELIX2.h +++ b/Marlin/pins_FELIX2.h @@ -30,16 +30,25 @@ #define BOARD_NAME "Felix 2.0+" +// +// Heaters / Fans +// // Power outputs EFBF or EFBE #define MOSFET_D_PIN 7 #include "pins_RAMPS.h" +// +// Misc. Functions +// #undef SDPOWER #define SDPOWER 1 #define PS_ON_PIN 12 +// +// LCD / Controller +// #if ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) #define SD_DETECT_PIN 6 diff --git a/Marlin/pins_GEN3_MONOLITHIC.h b/Marlin/pins_GEN3_MONOLITHIC.h index 85d5b3faef..e7a5dfb0d1 100644 --- a/Marlin/pins_GEN3_MONOLITHIC.h +++ b/Marlin/pins_GEN3_MONOLITHIC.h @@ -31,39 +31,45 @@ #define BOARD_NAME "Gen3 Monolithic" #define DEBUG_PIN 0 -// x axis -#define X_STEP_PIN 15 -#define X_DIR_PIN 18 -#define X_MIN_PIN 20 -// Alex Checar #define X_STOP_PIN 20 -#define X_ENABLE_PIN 24 // actually uses Y_enable_pin -#define X_MAX_PIN -1 +// +// Limit Switches +// +#define X_STOP_PIN 20 +#define Y_STOP_PIN 25 +#define Z_STOP_PIN 30 -// y axis -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_MIN_PIN 25 -// Alex Checar #define Y_STOP_PIN 25 -#define Y_ENABLE_PIN 24 // shared with X_enable_pin -#define Y_MAX_PIN -1 +// +// Steppers +// +#define X_STEP_PIN 15 +#define X_DIR_PIN 18 +#define X_ENABLE_PIN 24 // actually uses Y_enable_pin -// z axis -#define Z_STEP_PIN 27 -#define Z_DIR_PIN 28 -#define Z_MIN_PIN 30 -// Alex Checar #define Z_STOP_PIN 30 -#define Z_ENABLE_PIN 29 -#define Z_MAX_PIN -1 +#define Y_STEP_PIN 23 +#define Y_DIR_PIN 22 +#define Y_ENABLE_PIN 24 // shared with X_enable_pin -// extruder pins -#define E0_STEP_PIN 12 -#define E0_DIR_PIN 17 +#define Z_STEP_PIN 27 +#define Z_DIR_PIN 28 +#define Z_ENABLE_PIN 29 + +#define E0_STEP_PIN 12 +#define E0_DIR_PIN 17 #define E0_ENABLE_PIN 3 -#define HEATER_0_PIN 16 -#define TEMP_0_PIN 0 +// +// Temperature Sensors +// +#define TEMP_0_PIN 0 // Analog Input -// pin for controlling the PSU. -#define PS_ON_PIN 14 // Alex, Do this work on the card? +// +// Heaters +// +#define HEATER_0_PIN 16 + +// +// Misc. Functions +// +#define PS_ON_PIN 14 // Alex, does this work on the card? // Alex extras from Gen3+ diff --git a/Marlin/pins_GEN3_PLUS.h b/Marlin/pins_GEN3_PLUS.h index 7889a0103e..b5236d87ea 100644 --- a/Marlin/pins_GEN3_PLUS.h +++ b/Marlin/pins_GEN3_PLUS.h @@ -30,31 +30,47 @@ #define BOARD_NAME "Gen3+" +// +// Limit Switches +// +#define X_STOP_PIN 20 +#define Y_STOP_PIN 25 +#define Z_STOP_PIN 30 + +// +// Steppers +// #define X_STEP_PIN 15 #define X_DIR_PIN 18 -#define X_STOP_PIN 20 +#define X_ENABLE_PIN 19 #define Y_STEP_PIN 23 #define Y_DIR_PIN 22 -#define Y_STOP_PIN 25 +#define Y_ENABLE_PIN 24 #define Z_STEP_PIN 27 #define Z_DIR_PIN 28 -#define Z_STOP_PIN 30 +#define Z_ENABLE_PIN 29 #define E0_STEP_PIN 17 #define E0_DIR_PIN 21 - -#define PS_ON_PIN 14 - -#define HEATER_0_PIN 12 // (extruder) - -#define HEATER_BED_PIN 16 // (bed) -#define X_ENABLE_PIN 19 -#define Y_ENABLE_PIN 24 -#define Z_ENABLE_PIN 29 #define E0_ENABLE_PIN 13 -#define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder) -#define TEMP_BED_PIN 5 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed) -#define SDSS 4 +// +// Temperature Sensors +// +#define TEMP_0_PIN 0 // Analog Input (pin 33 extruder) +#define TEMP_BED_PIN 5 // Analog Input (pin 34 bed) + +// +// Heaters +// +#define HEATER_0_PIN 12 +#define HEATER_BED_PIN 16 + +// +// Misc. Functions +// +#define SDSS 4 +#define PS_ON_PIN 14 + diff --git a/Marlin/pins_GEN6.h b/Marlin/pins_GEN6.h index ae3d33a9ad..9d1e1bcf18 100644 --- a/Marlin/pins_GEN6.h +++ b/Marlin/pins_GEN6.h @@ -34,42 +34,53 @@ #define BOARD_NAME "Gen6" #endif -//x axis pins -#define X_STEP_PIN 15 -#define X_DIR_PIN 18 -#define X_ENABLE_PIN 19 -#define X_STOP_PIN 20 +// +// Limit Switches +// +#define X_STOP_PIN 20 +#define Y_STOP_PIN 25 +#define Z_STOP_PIN 30 -//y axis pins -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 -#define Y_STOP_PIN 25 +// +// Steppers +// +#define X_STEP_PIN 15 +#define X_DIR_PIN 18 +#define X_ENABLE_PIN 19 -//z axis pins -#define Z_STEP_PIN 27 -#define Z_DIR_PIN 28 -#define Z_ENABLE_PIN 29 -#define Z_STOP_PIN 30 +#define Y_STEP_PIN 23 +#define Y_DIR_PIN 22 +#define Y_ENABLE_PIN 24 -//extruder pins -#define E0_STEP_PIN 4 //Edited @ EJE Electronics 20100715 -#define E0_DIR_PIN 2 //Edited @ EJE Electronics 20100715 -#define E0_ENABLE_PIN 3 //Added @ EJE Electronics 20100715 -#define TEMP_0_PIN 5 //changed @ rkoeppl 20110410 +#define Z_STEP_PIN 27 +#define Z_DIR_PIN 28 +#define Z_ENABLE_PIN 29 -#define HEATER_0_PIN 14 //changed @ rkoeppl 20110410 +#define E0_STEP_PIN 4 // Edited @ EJE Electronics 20100715 +#define E0_DIR_PIN 2 // Edited @ EJE Electronics 20100715 +#define E0_ENABLE_PIN 3 // Added @ EJE Electronics 20100715 + +// +// Temperature Sensor +// +#define TEMP_0_PIN 5 // Analog Input + +// +// Heaters +// +#define HEATER_0_PIN 14 // changed @ rkoeppl 20110410 #if !MB(GEN6) - #define HEATER_BED_PIN 1 //changed @ rkoeppl 20110410 - #define TEMP_BED_PIN 0 //changed @ rkoeppl 20110410 + #define HEATER_BED_PIN 1 // changed @ rkoeppl 20110410 + #define TEMP_BED_PIN 0 // Analog Input #endif -#define SDSS 17 -//our pin for debugging. +// +// Misc. Functions +// +#define SDSS 17 +#define DEBUG_PIN 0 -#define DEBUG_PIN 0 - -//our RS485 pins -#define TX_ENABLE_PIN 12 -#define RX_ENABLE_PIN 13 +// RS485 pins +#define TX_ENABLE_PIN 12 +#define RX_ENABLE_PIN 13 diff --git a/Marlin/pins_GEN7_12.h b/Marlin/pins_GEN7_12.h index 1e59ae6fa9..53edb32811 100644 --- a/Marlin/pins_GEN7_12.h +++ b/Marlin/pins_GEN7_12.h @@ -36,52 +36,68 @@ #define GEN7_VERSION 12 // v1.x #endif -//x axis pins -#define X_STEP_PIN 19 -#define X_DIR_PIN 18 -#define X_ENABLE_PIN 24 -#define X_STOP_PIN 7 +// +// Limit Switches +// +#define X_STOP_PIN 7 +#define Y_STOP_PIN 5 +#define Z_MIN_PIN 1 +#define Z_MAX_PIN 0 -//y axis pins -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 -#define Y_STOP_PIN 5 - -//z axis pins -#define Z_STEP_PIN 26 -#define Z_DIR_PIN 25 -#define Z_ENABLE_PIN 24 -#define Z_MIN_PIN 1 -#define Z_MAX_PIN 0 - -//extruder pins -#define E0_STEP_PIN 28 -#define E0_DIR_PIN 27 -#define E0_ENABLE_PIN 24 - -#define TEMP_0_PIN 1 -#define TEMP_BED_PIN 2 - -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 3 - - -// Gen7 v1.3 removed the fan pin -#if GEN7_VERSION < 13 - #define FAN_PIN 31 +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 0 #endif -#define PS_ON_PIN 15 +// +// Steppers +// +#define X_STEP_PIN 19 +#define X_DIR_PIN 18 +#define X_ENABLE_PIN 24 -//All these generations of Gen7 supply thermistor power -//via PS_ON, so ignore bad thermistor readings +#define Y_STEP_PIN 23 +#define Y_DIR_PIN 22 +#define Y_ENABLE_PIN 24 + +#define Z_STEP_PIN 26 +#define Z_DIR_PIN 25 +#define Z_ENABLE_PIN 24 + +#define E0_STEP_PIN 28 +#define E0_DIR_PIN 27 +#define E0_ENABLE_PIN 24 + +// +// Temperature Sensors +// +#define TEMP_0_PIN 1 // Analog Input +#define TEMP_BED_PIN 2 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 4 +#define HEATER_BED_PIN 3 + +#if GEN7_VERSION < 13 // Gen7 v1.3 removed the fan pin + #define FAN_PIN 31 +#endif + +// +// Misc. Functions +// +#define PS_ON_PIN 15 + +// All these generations of Gen7 supply thermistor power +// via PS_ON, so ignore bad thermistor readings #define BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE -//our pin for debugging. -#define DEBUG_PIN 0 +#define DEBUG_PIN 0 -//our RS485 pins -#define TX_ENABLE_PIN 12 -#define RX_ENABLE_PIN 13 +// RS485 pins +#define TX_ENABLE_PIN 12 +#define RX_ENABLE_PIN 13 diff --git a/Marlin/pins_GEN7_14.h b/Marlin/pins_GEN7_14.h index 87ccb60186..d200137b48 100644 --- a/Marlin/pins_GEN7_14.h +++ b/Marlin/pins_GEN7_14.h @@ -32,40 +32,52 @@ #define GEN7_VERSION 14 // v1.4 -//x axis pins -#define X_STEP_PIN 29 -#define X_DIR_PIN 28 -#define X_ENABLE_PIN 25 -#define X_STOP_PIN 0 +// +// Limit switches +// +#define X_STOP_PIN 0 +#define Y_STOP_PIN 1 +#define Z_STOP_PIN 2 -//y axis pins -#define Y_STEP_PIN 27 -#define Y_DIR_PIN 26 -#define Y_ENABLE_PIN 25 -#define Y_STOP_PIN 1 +// +// Steppers +// +#define X_STEP_PIN 29 +#define X_DIR_PIN 28 +#define X_ENABLE_PIN 25 -//z axis pins -#define Z_STEP_PIN 23 -#define Z_DIR_PIN 22 -#define Z_ENABLE_PIN 25 -#define Z_STOP_PIN 2 +#define Y_STEP_PIN 27 +#define Y_DIR_PIN 26 +#define Y_ENABLE_PIN 25 -//extruder pins -#define E0_STEP_PIN 19 -#define E0_DIR_PIN 18 -#define E0_ENABLE_PIN 25 +#define Z_STEP_PIN 23 +#define Z_DIR_PIN 22 +#define Z_ENABLE_PIN 25 -#define TEMP_0_PIN 1 -#define TEMP_BED_PIN 0 +#define E0_STEP_PIN 19 +#define E0_DIR_PIN 18 +#define E0_ENABLE_PIN 25 +// +// Temperature Sensors +// +#define TEMP_0_PIN 1 // Analog Input +#define TEMP_BED_PIN 0 // Analog Input + +// +// Heaters +// #define HEATER_0_PIN 4 #define HEATER_BED_PIN 3 +// +// Misc. Functions +// #define PS_ON_PIN 15 -//our pin for debugging. +// A pin for debugging #define DEBUG_PIN 0 -//our RS485 pins +// RS485 pins #define TX_ENABLE_PIN 12 #define RX_ENABLE_PIN 13 diff --git a/Marlin/pins_GEN7_CUSTOM.h b/Marlin/pins_GEN7_CUSTOM.h index 06aaebd65e..81809d61ae 100644 --- a/Marlin/pins_GEN7_CUSTOM.h +++ b/Marlin/pins_GEN7_CUSTOM.h @@ -33,58 +33,71 @@ #define BOARD_NAME "Gen7 Custom" -//x axis pins -#define X_STEP_PIN 21 // different from standard GEN7 -#define X_DIR_PIN 20 // different from standard GEN7 -#define X_ENABLE_PIN 24 +// +// Limit Switches +// #define X_STOP_PIN 0 +#define Y_STOP_PIN 1 +#define Z_STOP_PIN 2 + +// +// Steppers +// +#define X_STEP_PIN 21 // different from standard GEN7 +#define X_DIR_PIN 20 // different from standard GEN7 +#define X_ENABLE_PIN 24 -//y axis pins #define Y_STEP_PIN 23 #define Y_DIR_PIN 22 #define Y_ENABLE_PIN 24 -#define Y_STOP_PIN 1 -//z axis pins #define Z_STEP_PIN 26 #define Z_DIR_PIN 25 #define Z_ENABLE_PIN 24 -#define Z_STOP_PIN 2 -//extruder pins #define E0_STEP_PIN 28 #define E0_DIR_PIN 27 #define E0_ENABLE_PIN 24 -#define TEMP_0_PIN 2 -#define TEMP_BED_PIN 1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed) +// +// Temperature Sensors +// +#define TEMP_0_PIN 2 // Analog Input +#define TEMP_BED_PIN 1 // Analog Input (pin 34 bed) +// +// Heaters +// #define HEATER_0_PIN 4 #define HEATER_BED_PIN 3 // (bed) -#define SDSS 31 // SCL pin of I2C header || CS Pin for SD Card support - +// +// Misc. Functions +// +#define SDSS 31 // SCL pin of I2C header || CS Pin for SD Card support #define PS_ON_PIN 19 -//our pin for debugging. +// A pin for debugging #define DEBUG_PIN -1 -//our RS485 pins -//#define TX_ENABLE_PIN 12 -//#define RX_ENABLE_PIN 13 +// +// LCD / Controller +// +#define BEEPER_PIN -1 -#define BEEPER_PIN -1 - -//Pins for 4bit LCD Support -#define LCD_PINS_RS 18 +// 4bit LCD Support +#define LCD_PINS_RS 18 #define LCD_PINS_ENABLE 17 -#define LCD_PINS_D4 16 -#define LCD_PINS_D5 15 -#define LCD_PINS_D6 13 -#define LCD_PINS_D7 14 +#define LCD_PINS_D4 16 +#define LCD_PINS_D5 15 +#define LCD_PINS_D6 13 +#define LCD_PINS_D7 14 -//buttons are directly attached -#define BTN_EN1 11 -#define BTN_EN2 10 -#define BTN_ENC 12 +// Buttons are directly attached +#define BTN_EN1 11 +#define BTN_EN2 10 +#define BTN_ENC 12 +// RS485 pins +//#define TX_ENABLE_PIN 12 +//#define RX_ENABLE_PIN 13 diff --git a/Marlin/pins_K8400.h b/Marlin/pins_K8400.h index a15e9e4949..030546c93d 100644 --- a/Marlin/pins_K8400.h +++ b/Marlin/pins_K8400.h @@ -37,16 +37,31 @@ #include "pins_3DRAG.h" -#undef X_MAX_PIN -#define X_MAX_PIN -1 -#undef Y_MAX_PIN -#define Y_MAX_PIN -1 +// +// Limit Switches +// +#define X_STOP_PIN 3 +#define Y_STOP_PIN 14 +#undef X_MIN_PIN +#undef X_MAX_PIN +#undef Y_MIN_PIN +#undef Y_MAX_PIN + +// +// Steppers +// #undef E1_STEP_PIN #define E1_STEP_PIN 32 -#undef PS_ON_PIN -#undef KILL_PIN - +// +// Heaters / Fans +// #undef HEATER_1_PIN #define HEATER_1_PIN 11 + +// +// Misc. Functions +// +#undef PS_ON_PIN +#undef KILL_PIN diff --git a/Marlin/pins_LEAPFROG.h b/Marlin/pins_LEAPFROG.h index acfba03731..a7fffa5325 100644 --- a/Marlin/pins_LEAPFROG.h +++ b/Marlin/pins_LEAPFROG.h @@ -30,44 +30,62 @@ #define BOARD_NAME "Leapfrog" +// +// Limit Switches +// +#define X_MIN_PIN 47 +#define X_MAX_PIN 2 +#define Y_MIN_PIN 48 +#define Y_MAX_PIN 15 +#define Z_MIN_PIN 49 +#define Z_MAX_PIN -1 + +// +// Steppers +// #define X_STEP_PIN 28 #define X_DIR_PIN 63 #define X_ENABLE_PIN 29 -#define X_MIN_PIN 47 -#define X_MAX_PIN 2 //Max endstops default to disabled "-1", set to commented value to enable. #define Y_STEP_PIN 14 // A6 #define Y_DIR_PIN 15 // A0 #define Y_ENABLE_PIN 39 -#define Y_MIN_PIN 48 -#define Y_MAX_PIN 15 #define Z_STEP_PIN 31 // A2 #define Z_DIR_PIN 32 // A6 #define Z_ENABLE_PIN 30 // A1 -#define Z_MIN_PIN 49 -#define Z_MAX_PIN -1 -#define E0_STEP_PIN 34 //34 -#define E0_DIR_PIN 35 //35 -#define E0_ENABLE_PIN 33 //33 +#define E0_STEP_PIN 34 // 34 +#define E0_DIR_PIN 35 // 35 +#define E0_ENABLE_PIN 33 // 33 -#define E1_STEP_PIN 37 //37 -#define E1_DIR_PIN 40 //40 -#define E1_ENABLE_PIN 36 //36 +#define E1_STEP_PIN 37 // 37 +#define E1_DIR_PIN 40 // 40 +#define E1_ENABLE_PIN 36 // 36 +// +// Temperature Sensors +// +#define TEMP_0_PIN 13 // Analog Input (D27) +#define TEMP_1_PIN 15 // Analog Input (1) +#define TEMP_BED_PIN 14 // Analog Input (1,2 or I2C) + +// +// Heaters / Fans +// +#define HEATER_0_PIN 9 +#define HEATER_1_PIN 8 // 12 +#define HEATER_2_PIN 11 // 13 +#define HEATER_BED_PIN 10 // 14/15 + +#define FAN_PIN 7 + +// +// Misc. Functions +// #define SDSS 11 #define LED_PIN 13 -#define FAN_PIN 7 -#define SOL1_PIN 16 -#define SOL2_PIN 17 +#define SOL1_PIN 16 +#define SOL2_PIN 17 -#define HEATER_0_PIN 9 -#define HEATER_1_PIN 8 // 12 -#define HEATER_2_PIN 11 //-1 // 13 -#define TEMP_0_PIN 13 //D27 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! -#define TEMP_1_PIN 15 // 1 -#define HEATER_BED_PIN 10 // 14/15 -#define TEMP_BED_PIN 14 // 1,2 or I2C /* Unused (1) (2) (3) 4 5 6 7 8 9 10 11 12 13 (14) (15) (16) 17 (18) (19) (20) (21) (22) (23) 24 (25) (26) (27) 28 (29) (30) (31) */ - diff --git a/Marlin/pins_MEGACONTROLLER.h b/Marlin/pins_MEGACONTROLLER.h index 7ea4ee34b7..10ffe3283a 100644 --- a/Marlin/pins_MEGACONTROLLER.h +++ b/Marlin/pins_MEGACONTROLLER.h @@ -34,79 +34,109 @@ #define BOARD_NAME "Mega Controller" -#define SERVO0_PIN 30 -#define SERVO1_PIN 31 -#define SERVO2_PIN 32 -#define SERVO3_PIN 33 +// +// Servos +// +#define SERVO0_PIN 30 +#define SERVO1_PIN 31 +#define SERVO2_PIN 32 +#define SERVO3_PIN 33 -#define X_STEP_PIN 62//A8 -#define X_DIR_PIN 63//A9 -#define X_ENABLE_PIN 61//A7 -#define X_MIN_PIN 43 -#define X_MAX_PIN 42 //Max endstops default to disabled "-1", set to commented value to enable. +// +// Limit Switches +// +#define X_MIN_PIN 43 +#define X_MAX_PIN 42 +#define Y_MIN_PIN 38 +#define Y_MAX_PIN 41 +#define Z_MIN_PIN 40 +#define Z_MAX_PIN 37 -#define Y_STEP_PIN 65 // A11 -#define Y_DIR_PIN 66 // A12 -#define Y_ENABLE_PIN 64//A10 -#define Y_MIN_PIN 38 -#define Y_MAX_PIN 41 +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 37 +#endif -#define Z_STEP_PIN 68 // A14 -#define Z_DIR_PIN 69 // A15 -#define Z_ENABLE_PIN 67 // A13 -#define Z_MIN_PIN 40 -#define Z_MAX_PIN 37 +// +// Steppers +// +#define X_STEP_PIN 62 // A8 +#define X_DIR_PIN 63 // A9 +#define X_ENABLE_PIN 61 // A7 -#define E0_STEP_PIN 23 -#define E0_DIR_PIN 24 -#define E0_ENABLE_PIN 22 +#define Y_STEP_PIN 65 // A11 +#define Y_DIR_PIN 66 // A12 +#define Y_ENABLE_PIN 64 // A10 -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 27 -#define E1_ENABLE_PIN 25 +#define Z_STEP_PIN 68 // A14 +#define Z_DIR_PIN 69 // A15 +#define Z_ENABLE_PIN 67 // A13 -#define SDSS 53 -#define LED_PIN 13 +#define E0_STEP_PIN 23 +#define E0_DIR_PIN 24 +#define E0_ENABLE_PIN 22 -#define FAN_PIN 39 -#define FAN1_PIN 35 -#define FAN2_PIN 36 -#define FAN_SOFT_PWM -#define CONTROLLERFAN_PIN FAN2_PIN - -#define HEATER_0_PIN 29 // EXTRUDER 1 -#define HEATER_1_PIN 34 // EXTRUDER 2 +#define E1_STEP_PIN 26 +#define E1_DIR_PIN 27 +#define E1_ENABLE_PIN 25 +// +// Temperature Sensors +// #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 4 // ANALOG NUMBERING + #define TEMP_0_PIN 4 // Analog Input #else - #define TEMP_0_PIN 0 // ANALOG NUMBERING + #define TEMP_0_PIN 0 // Analog Input #endif #if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 5 // ANALOG NUMBERING + #define TEMP_1_PIN 5 // Analog Input #else - #define TEMP_1_PIN 2 // ANALOG NUMBERING + #define TEMP_1_PIN 2 // Analog Input #endif -#define TEMP_2_PIN 3 // ANALOG NUMBERING - -#define HEATER_BED_PIN 28 // BED +#define TEMP_2_PIN 3 // Analog Input #if TEMP_SENSOR_BED == -1 - #define TEMP_BED_PIN 6 // ANALOG NUMBERING + #define TEMP_BED_PIN 6 // Analog Input #else - #define TEMP_BED_PIN 1 // ANALOG NUMBERING + #define TEMP_BED_PIN 1 // Analog Input #endif -#if ENABLED(MINIPANEL) - #define BEEPER_PIN 46 - // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 47 - #define DOGLCD_CS 45 - #define LCD_PIN_BL 44 // backlight LED on PA3 +// +// Heaters / Fans +// +#define HEATER_0_PIN 29 +#define HEATER_1_PIN 34 +#define HEATER_BED_PIN 28 - #define KILL_PIN 12 +#define FAN_PIN 39 +#define FAN1_PIN 35 +#define FAN2_PIN 36 + +#define CONTROLLERFAN_PIN FAN2_PIN + +#define FAN_SOFT_PWM + +// +// Misc. Functions +// +#define SDSS 53 +#define LED_PIN 13 + +// +// LCD / Controller +// +#if ENABLED(MINIPANEL) + #define BEEPER_PIN 46 + // Pins for DOGM SPI LCD Support + #define DOGLCD_A0 47 + #define DOGLCD_CS 45 + #define LCD_BACKLIGHT_PIN 44 // backlight LED on PA3 + + #define KILL_PIN 12 // GLCD features //#define LCD_CONTRAST 190 // Uncomment screen orientation @@ -114,10 +144,9 @@ //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 - #define BTN_EN1 48 - #define BTN_EN2 11 - #define BTN_ENC 10 + #define BTN_EN1 48 + #define BTN_EN2 11 + #define BTN_ENC 10 - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN 49 #endif // MINIPANEL - diff --git a/Marlin/pins_MEGATRONICS.h b/Marlin/pins_MEGATRONICS.h index 1b95f525fc..5b8d41f4f5 100644 --- a/Marlin/pins_MEGATRONICS.h +++ b/Marlin/pins_MEGATRONICS.h @@ -31,23 +31,37 @@ #define BOARD_NAME "Megatronics" #define LARGE_FLASH true +// +// Limit Switches +// +#define X_MIN_PIN 41 +#define X_MAX_PIN 37 +#define Y_MIN_PIN 14 +#define Y_MAX_PIN 15 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 19 +#endif + +// +// Steppers +// #define X_STEP_PIN 26 #define X_DIR_PIN 28 #define X_ENABLE_PIN 24 -#define X_MIN_PIN 41 -#define X_MAX_PIN 37 #define Y_STEP_PIN 60 // A6 #define Y_DIR_PIN 61 // A7 #define Y_ENABLE_PIN 22 -#define Y_MIN_PIN 14 -#define Y_MAX_PIN 15 #define Z_STEP_PIN 54 // A0 #define Z_DIR_PIN 55 // A1 #define Z_ENABLE_PIN 56 // A2 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 #define E0_STEP_PIN 31 #define E0_DIR_PIN 32 @@ -57,25 +71,36 @@ #define E1_DIR_PIN 36 #define E1_ENABLE_PIN 30 -#define SDSS 53 -#define LED_PIN 13 - -#define FAN_PIN 7 // IO pin. Buffer needed -#define PS_ON_PIN 12 +// +// Temperature Sensors +// +#if TEMP_SENSOR_0 == -1 + #define TEMP_0_PIN 8 // Analog Input +#else + #define TEMP_0_PIN 13 // Analog Input +#endif +#define TEMP_1_PIN 15 // Analog Input +#define TEMP_BED_PIN 14 // Analog Input +// +// Heaters / Fans +// #define HEATER_0_PIN 9 #define HEATER_1_PIN 8 -#define HEATER_BED_PIN 10 // BED +#define HEATER_BED_PIN 10 -#if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 8 // ANALOG NUMBERING -#else - #define TEMP_0_PIN 13 // ANALOG NUMBERING -#endif -#define TEMP_1_PIN 15 // ANALOG NUMBERING -#define TEMP_BED_PIN 14 // ANALOG NUMBERING +#define FAN_PIN 7 // IO pin. Buffer needed -// AUX-4 +// +// Misc. Functions +// +#define SDSS 53 +#define LED_PIN 13 +#define PS_ON_PIN 12 + +// +// LCD / Controller +// #define BEEPER_PIN 33 #if ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) diff --git a/Marlin/pins_MEGATRONICS_2.h b/Marlin/pins_MEGATRONICS_2.h index 991ab4a9cc..be3ed4cf4a 100644 --- a/Marlin/pins_MEGATRONICS_2.h +++ b/Marlin/pins_MEGATRONICS_2.h @@ -31,74 +31,101 @@ #define BOARD_NAME "Megatronics v2.0" #define LARGE_FLASH true -#define X_STEP_PIN 26 -#define X_DIR_PIN 27 -#define X_ENABLE_PIN 25 -#define X_MIN_PIN 37 -#define X_MAX_PIN 40 +// +// Limit Switches +// +#define X_MIN_PIN 37 +#define X_MAX_PIN 40 +#define Y_MIN_PIN 41 +#define Y_MAX_PIN 38 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 -#define Y_STEP_PIN 4 // A6 -#define Y_DIR_PIN 54 // A0 -#define Y_ENABLE_PIN 5 -#define Y_MIN_PIN 41 -#define Y_MAX_PIN 38 +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 19 +#endif -#define Z_STEP_PIN 56 // A2 -#define Z_DIR_PIN 60 // A6 -#define Z_ENABLE_PIN 55 // A1 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +// +// Steppers +// +#define X_STEP_PIN 26 +#define X_DIR_PIN 27 +#define X_ENABLE_PIN 25 -#define E0_STEP_PIN 35 -#define E0_DIR_PIN 36 -#define E0_ENABLE_PIN 34 +#define Y_STEP_PIN 4 // A6 +#define Y_DIR_PIN 54 // A0 +#define Y_ENABLE_PIN 5 -#define E1_STEP_PIN 29 -#define E1_DIR_PIN 39 -#define E1_ENABLE_PIN 28 +#define Z_STEP_PIN 56 // A2 +#define Z_DIR_PIN 60 // A6 +#define Z_ENABLE_PIN 55 // A1 -#define E2_STEP_PIN 23 -#define E2_DIR_PIN 24 -#define E2_ENABLE_PIN 22 +#define E0_STEP_PIN 35 +#define E0_DIR_PIN 36 +#define E0_ENABLE_PIN 34 -#define SDSS 53 -#define LED_PIN 13 +#define E1_STEP_PIN 29 +#define E1_DIR_PIN 39 +#define E1_ENABLE_PIN 28 -#define FAN_PIN 7 -#define FAN2_PIN 6 -#define PS_ON_PIN 12 +#define E2_STEP_PIN 23 +#define E2_DIR_PIN 24 +#define E2_ENABLE_PIN 22 -#define HEATER_0_PIN 9 // EXTRUDER 1 +// +// Temperature Sensors +// #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 4 // ANALOG NUMBERING + #define TEMP_0_PIN 4 // Analog Input #else - #define TEMP_0_PIN 13 // ANALOG NUMBERING + #define TEMP_0_PIN 13 // Analog Input #endif -#define HEATER_1_PIN 8 // EXTRUDER 2 #if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 8 // ANALOG NUMBERING + #define TEMP_1_PIN 8 // Analog Input #else - #define TEMP_1_PIN 15 // ANALOG NUMBERING + #define TEMP_1_PIN 15 // Analog Input #endif -#define HEATER_BED_PIN 10 // BED #if TEMP_SENSOR_BED == -1 - #define TEMP_BED_PIN 8 // ANALOG NUMBERING + #define TEMP_BED_PIN 8 // Analog Input #else - #define TEMP_BED_PIN 14 // ANALOG NUMBERING + #define TEMP_BED_PIN 14 // Analog Input #endif -#define BEEPER_PIN 64 +// +// Heaters / Fans +// +#define HEATER_0_PIN 9 +#define HEATER_1_PIN 8 +#define HEATER_BED_PIN 10 -#define LCD_PINS_RS 14 -#define LCD_PINS_ENABLE 15 -#define LCD_PINS_D4 30 -#define LCD_PINS_D5 31 -#define LCD_PINS_D6 32 -#define LCD_PINS_D7 33 +#define FAN_PIN 7 +#define FAN1_PIN 6 + +// +// Misc. Functions +// +#define SDSS 53 +#define LED_PIN 13 +#define PS_ON_PIN 12 + +// +// LCD / Controller +// +#define BEEPER_PIN 64 + +#define LCD_PINS_RS 14 +#define LCD_PINS_ENABLE 15 +#define LCD_PINS_D4 30 +#define LCD_PINS_D5 31 +#define LCD_PINS_D6 32 +#define LCD_PINS_D7 33 // Buttons are directly attached using keypad -#define BTN_EN1 61 -#define BTN_EN2 59 -#define BTN_ENC 43 +#define BTN_EN1 61 +#define BTN_EN2 59 +#define BTN_ENC 43 diff --git a/Marlin/pins_MEGATRONICS_3.h b/Marlin/pins_MEGATRONICS_3.h index a983ee2a7d..1b87457e23 100644 --- a/Marlin/pins_MEGATRONICS_3.h +++ b/Marlin/pins_MEGATRONICS_3.h @@ -28,8 +28,6 @@ #error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu." #endif -#define MEGATRONICS_31 - #if ENABLED(MEGATRONICS_31) #define BOARD_NAME "Megatronics v3.1" #else @@ -38,33 +36,47 @@ #define LARGE_FLASH true -#if ENABLED(Z_PROBE_SLED) - #define SLED_PIN -1 -#endif - -// Servo support +// +// Servos +// #define SERVO0_PIN 46 // AUX3-6 #define SERVO1_PIN 47 // AUX3-5 #define SERVO2_PIN 48 // AUX3-4 #define SERVO3_PIN 49 // AUX3-3 +// +// Limit Switches +// +#define X_MIN_PIN 37 +#define X_MAX_PIN 40 +#define Y_MIN_PIN 41 +#define Y_MAX_PIN 38 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 19 +#endif + +#define SLED_PIN -1 + +// +// Steppers +// #define X_STEP_PIN 58 #define X_DIR_PIN 57 #define X_ENABLE_PIN 59 -#define X_MIN_PIN 37 -#define X_MAX_PIN 40 -#define Y_STEP_PIN 5 +#define Y_STEP_PIN 5 #define Y_DIR_PIN 17 -#define Y_ENABLE_PIN 4 -#define Y_MIN_PIN 41 -#define Y_MAX_PIN 38 +#define Y_ENABLE_PIN 4 #define Z_STEP_PIN 16 #define Z_DIR_PIN 11 -#define Z_ENABLE_PIN 3 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 +#define Z_ENABLE_PIN 3 #define E0_STEP_PIN 28 #define E0_DIR_PIN 27 @@ -78,70 +90,79 @@ #define E2_DIR_PIN 60 #define E2_ENABLE_PIN 23 -#define SDSS 53 -#define LED_PIN 13 - -#define PS_ON_PIN 12 - -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 9 -#define HEATER_2_PIN 8 -#define HEATER_BED_PIN 10 -#define FAN_PIN 6 -#define FAN2_PIN 7 - +// +// Temperature Sensors +// #if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 11 // ANALOG NUMBERING + #define TEMP_0_PIN 11 // Analog Input #else - #define TEMP_0_PIN 15 // ANALOG NUMBERING + #define TEMP_0_PIN 15 // Analog Input #endif #if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 10 // ANALOG NUMBERING + #define TEMP_1_PIN 10 // Analog Input #else - #define TEMP_1_PIN 13 // ANALOG NUMBERING + #define TEMP_1_PIN 13 // Analog Input #endif #if TEMP_SENSOR_2 == -1 - #define TEMP_2_PIN 9 // ANALOG NUMBERING + #define TEMP_2_PIN 9 // Analog Input #else - #define TEMP_2_PIN 12 // ANALOG NUMBERING + #define TEMP_2_PIN 12 // Analog Input #endif #if TEMP_SENSOR_BED == -1 - #define TEMP_BED_PIN 8 // ANALOG NUMBERING + #define TEMP_BED_PIN 8 // Analog Input #else - #define TEMP_BED_PIN 14 // ANALOG NUMBERING + #define TEMP_BED_PIN 14 // Analog Input #endif -/** - * Controllers and LCDs - */ -#define BEEPER_PIN 61 +// +// Heaters / Fans +// +#define HEATER_0_PIN 2 +#define HEATER_1_PIN 9 +#define HEATER_2_PIN 8 +#define HEATER_BED_PIN 10 -#define BTN_EN1 44 -#define BTN_EN2 45 -#define BTN_ENC 33 +#define FAN_PIN 6 +#define FAN1_PIN 7 + +// +// Misc. Functions +// +#define SDSS 53 +#define LED_PIN 13 +#define PS_ON_PIN 12 + +// +// LCD / Controller +// +#define BEEPER_PIN 61 + +#define BTN_EN1 44 +#define BTN_EN2 45 +#define BTN_ENC 33 #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 56 // CS chip select / SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock - #define SD_DETECT_PIN 35 + #define LCD_PINS_RS 56 // CS chip select / SS chip slave select + #define LCD_PINS_ENABLE 51 // SID (MOSI) + #define LCD_PINS_D4 52 // SCK (CLK) clock + #define SD_DETECT_PIN 35 #else - #define LCD_PINS_RS 32 - #define LCD_PINS_ENABLE 31 - #define LCD_PINS_D4 14 - #define LCD_PINS_D5 30 - #define LCD_PINS_D6 39 - #define LCD_PINS_D7 15 + #define LCD_PINS_RS 32 + #define LCD_PINS_ENABLE 31 + #define LCD_PINS_D4 14 + #define LCD_PINS_D5 30 + #define LCD_PINS_D6 39 + #define LCD_PINS_D7 15 - #define SHIFT_CLK 43 - #define SHIFT_LD 35 - #define SHIFT_OUT 34 - #define SHIFT_EN 44 + #define SHIFT_CLK 43 + #define SHIFT_LD 35 + #define SHIFT_OUT 34 + #define SHIFT_EN 44 #if ENABLED(MEGATRONICS_31) - #define SD_DETECT_PIN 56 + #define SD_DETECT_PIN 56 #else - #define SD_DETECT_PIN -1 + #define SD_DETECT_PIN -1 #endif #endif diff --git a/Marlin/pins_MIGHTYBOARD_REVE.h b/Marlin/pins_MIGHTYBOARD_REVE.h new file mode 100644 index 0000000000..cb85534d32 --- /dev/null +++ b/Marlin/pins_MIGHTYBOARD_REVE.h @@ -0,0 +1,222 @@ +/** + * 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 . + * + */ + +/** + * Mightyboard Rev.E pin assignments + */ + +/** + * + * This is a starting-point to support the Makerbot Replicator series of 3D printers. + * It's not functional because Marlin has limited support for some features. + * Marlin will need the following augmentations before it will be supportable: + * + * - Support for two or more MAX6675 thermocouples + * - Support for multiple i2c buses to control the MCP4018 digital pots + * - Support for one additional unidirectional SPI bus, to read the thermocouples + * - Support for an RGB LED that may work differently from BLINKM + * + * The MCP4018 requires separate I2C buses because it has a fixed address (0x2F << 1 = 0x5E) + * The thermocouples share the same SCK and DO pins, with their own CS pins. + * The controller interface port connects to a 3-wire shift-register display controller + * + */ + +#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) + #error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu." +#endif + +#define DEFAULT_MACHINE_NAME "MB Replicator" +#define BOARD_NAME "Mightyboard" + +#define LARGE_FLASH true + +// +// Servos +// +#define SERVO0_PIN 36 // C1 (1280-EX1) +#define SERVO1_PIN 37 // C0 (1280-EX2) +#define SERVO2_PIN 40 // G1 (1280-EX3) +#define SERVO3_PIN 41 // G0 (1280-EX4) + +// +// Limit Switches +// +#define X_MIN_PIN 49 // L0 +#define X_MAX_PIN 48 // L1 +#define Y_MIN_PIN 47 // L2 +#define Y_MAX_PIN 46 // L3 +#define Z_MIN_PIN 43 // L6 +#define Z_MAX_PIN 42 // L7 + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 42 +#endif + +// +// Steppers +// +#define X_STEP_PIN 55 // F1 +#define X_DIR_PIN 54 // F0 +#define X_ENABLE_PIN 56 // F2 + +#define Y_STEP_PIN 59 // F5 +#define Y_DIR_PIN 58 // F4 +#define Y_ENABLE_PIN 60 // F6 + +#define Z_STEP_PIN 63 // K1 +#define Z_DIR_PIN 62 // K0 +#define Z_ENABLE_PIN 64 // K2 + +#define E0_STEP_PIN 25 // A3 +#define E0_DIR_PIN 24 // A2 +#define E0_ENABLE_PIN 26 // A4 + +#define E1_STEP_PIN 29 // A7 +#define E1_DIR_PIN 28 // A6 +#define E1_ENABLE_PIN 39 // G2 + +// +// I2C Digipots - MCP4018 +// Address 5E (2F << 1) +// Set from 0 - 127 with stop bit. +// (Ex. 3F << 1 | 1) +// +#define DIGIPOTS_I2C_SCL 76 // J5 +#define DIGIPOTS_I2C_SDA_X 57 // F3 +#define DIGIPOTS_I2C_SDA_Y 61 // F7 +#define DIGIPOTS_I2C_SDA_Z 65 // K3 +#define DIGIPOTS_I2C_SDA_E0 27 // A5 +#define DIGIPOTS_I2C_SDA_E1 77 // J6 + +// +// Temperature Sensors +// +#define TEMP_BED_PIN 69 // K7 + +// SPI for Max6675 or Max31855 Thermocouple +// Uses a separate SPI bus +// +// 3 E5 DO (SO) +// 5 E3 CS1 +// 2 E4 CS2 +// 78 E2 SCK +// +#define THERMO_SCK_PIN 78 // E2 +#define THERMO_DO_PIN 3 // E5 +#define THERMO_CS1 5 // E3 +#define THERMO_CS2 2 // E4 + +// +// Augmentation for auto-assigning plugs +// +// Two thermocouple connectors allows for either +// 2 extruders or 1 extruder and a heated bed. +// With no heated bed, an additional 24V fan is possible. +// +#define MOSFET_A_PIN 6 // H3 +#define MOSFET_B_PIN 9 // B5 +#define MOSFET_C_PIN 45 // L4 +#define MOSFET_D_PIN 44 // L5 + +#if HOTENDS > 1 + #if TEMP_SENSOR_BED + #define IS_EEB + #else + #define IS_EEF + #endif +#elif TEMP_SENSOR_BED + #define IS_EFB +#else + #define IS_EFF +#endif + +// +// Heaters / Fans (24V) +// +#define HEATER_0_PIN MOSFET_A_PIN + +#if ENABLED(IS_EFB) // Hotend, Fan, Bed + #define FAN_PIN MOSFET_B_PIN + #define HEATER_BED_PIN MOSFET_C_PIN +#elif ENABLED(IS_EEF) // Hotend, Hotend, Fan + #define HEATER_1_PIN MOSFET_B_PIN + #define FAN_PIN MOSFET_C_PIN +#elif ENABLED(IS_EEB) // Hotend, Hotend, Bed + #define HEATER_1_PIN MOSFET_B_PIN + #define HEATER_BED_PIN MOSFET_C_PIN +#elif ENABLED(IS_EFF) // Hotend, Fan, Fan + #define FAN_PIN MOSFET_B_PIN + #define FAN1_PIN MOSFET_C_PIN +#elif ENABLED(IS_SF) // Spindle, Fan + #define FAN_PIN MOSFET_C_PIN +#endif + +#ifndef FAN_PIN + #define FAN_PIN MOSFET_D_PIN +#endif + +// +// Extruder Auto Fan Pins +// +#define EXTRUDER_0_AUTO_FAN 7 // H4 +#define EXTRUDER_1_AUTO_FAN 12 // B6 + +// +// Misc. Functions +// +#define LED_PIN 13 // B7 +#define CUTOFF_RESET_PIN 16 // H1 +#define CUTOFF_TEST_PIN 17 // H0 + +// +// LCD / Controller +// +// Replicator uses a 3-wire SR controller with HD44780 +// For now, pretend it's the SAV +// +#define SAV_3DLCD +#define SR_DATA_PIN 34 // C3 +#define SR_CLK_PIN 35 // C2 +#define SR_STROBE_PIN 33 // C4 + +#define BTN_UP 75 // J4 +#define BTN_DOWN 73 // J3 +#define BTN_LEFT 72 // J2 +#define BTN_RIGHT 14 // J1 +#define BTN_CENTER 15 // J0 +#define BTN_ENC BTN_CENTER + +#define BEEPER_PIN 4 // G5 + +#define STAT_LED_RED 32 // C5 +#define STAT_LED_BLUE 31 // C6 (Actually green) + +// +// SD Card +// +#define SDSS 53 // B0 +#define SD_DETECT_PIN 30 // C7 + diff --git a/Marlin/pins_MINIRAMBO.h b/Marlin/pins_MINIRAMBO.h index 089ea59963..551926a5fa 100644 --- a/Marlin/pins_MINIRAMBO.h +++ b/Marlin/pins_MINIRAMBO.h @@ -31,86 +31,112 @@ #define BOARD_NAME "Mini Rambo" #define LARGE_FLASH true -#define X_STEP_PIN 37 -#define X_DIR_PIN 48 -#define X_MIN_PIN 12 -#define X_MAX_PIN 30 -#define X_ENABLE_PIN 29 -#define X_MS1_PIN 40 -#define X_MS2_PIN 41 +// +// Limit Switches +// +#define X_MIN_PIN 12 +#define X_MAX_PIN 30 +#define Y_MIN_PIN 11 +#define Y_MAX_PIN 24 +#define Z_MIN_PIN 10 +#define Z_MAX_PIN 23 -#define Y_STEP_PIN 36 -#define Y_DIR_PIN 49 -#define Y_MIN_PIN 11 -#define Y_MAX_PIN 24 -#define Y_ENABLE_PIN 28 -#define Y_MS1_PIN 69 -#define Y_MS2_PIN 39 - -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 47 -#define Z_MIN_PIN 10 -#define Z_MAX_PIN 23 -#define Z_ENABLE_PIN 27 -#define Z_MS1_PIN 68 -#define Z_MS2_PIN 67 - -#define HEATER_BED_PIN 4 -#define TEMP_BED_PIN 2 - -#define HEATER_0_PIN 3 -#define TEMP_0_PIN 0 - -#define HEATER_1_PIN 7 -#define TEMP_1_PIN 1 - -#if ENABLED(BARICUDA) - #define HEATER_2_PIN 6 +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 23 #endif -#define E0_STEP_PIN 34 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 26 -#define E0_MS1_PIN 65 -#define E0_MS2_PIN 66 +// +// Steppers +// +#define X_STEP_PIN 37 +#define X_DIR_PIN 48 +#define X_ENABLE_PIN 29 -#define E1_STEP_PIN -1 -#define E1_DIR_PIN -1 -#define E1_ENABLE_PIN -1 +#define Y_STEP_PIN 36 +#define Y_DIR_PIN 49 +#define Y_ENABLE_PIN 28 + +#define Z_STEP_PIN 35 +#define Z_DIR_PIN 47 +#define Z_ENABLE_PIN 27 + +#define E0_STEP_PIN 34 +#define E0_DIR_PIN 43 +#define E0_ENABLE_PIN 26 + +#define E1_STEP_PIN -1 +#define E1_DIR_PIN -1 +#define E1_ENABLE_PIN -1 + +// Microstepping pins - Mapping not from fastio.h (?) +#define X_MS1_PIN 40 +#define X_MS2_PIN 41 +#define Y_MS1_PIN 69 +#define Y_MS2_PIN 39 +#define Z_MS1_PIN 68 +#define Z_MS2_PIN 67 +#define E0_MS1_PIN 65 +#define E0_MS2_PIN 66 #define MOTOR_CURRENT_PWM_XY_PIN 46 #define MOTOR_CURRENT_PWM_Z_PIN 45 #define MOTOR_CURRENT_PWM_E_PIN 44 -//Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range +// Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range #define MOTOR_CURRENT_PWM_RANGE 2000 #define DEFAULT_PWM_MOTOR_CURRENT {1300, 1300, 1250} -#define SDSS 53 -#define LED_PIN 13 -#define FAN_PIN 8 -#define FAN_1_PIN 6 +// +// Temperature Sensors +// +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 1 // Analog Input +#define TEMP_BED_PIN 2 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 3 +#define HEATER_1_PIN 7 +#define HEATER_2_PIN 6 +#define HEATER_BED_PIN 4 + +#define FAN_PIN 8 +#define FAN1_PIN 6 + +// +// Misc. Functions +// +#define SDSS 53 +#define LED_PIN 13 + +// +// LCD / Controller +// #if ENABLED(ULTRA_LCD) - #define KILL_PIN 32 + #define KILL_PIN 32 #if ENABLED(NEWPANEL) // Beeper on AUX-4 - #define BEEPER_PIN 84 + #define BEEPER_PIN 84 - #define LCD_PINS_RS 82 + #define LCD_PINS_RS 82 #define LCD_PINS_ENABLE 18 - #define LCD_PINS_D4 19 - #define LCD_PINS_D5 70 - #define LCD_PINS_D6 85 - #define LCD_PINS_D7 71 + #define LCD_PINS_D4 19 + #define LCD_PINS_D5 70 + #define LCD_PINS_D6 85 + #define LCD_PINS_D7 71 - //buttons are directly attached using AUX-2 - #define BTN_EN1 14 - #define BTN_EN2 72 - #define BTN_ENC 9 // the click + // buttons are directly attached using AUX-2 + #define BTN_EN1 14 + #define BTN_EN2 72 + #define BTN_ENC 9 // the click - #define SD_DETECT_PIN 15 + #define SD_DETECT_PIN 15 - #endif //NEWPANEL -#endif //ULTRA_LCD + #endif // NEWPANEL +#endif // ULTRA_LCD diff --git a/Marlin/pins_MINITRONICS.h b/Marlin/pins_MINITRONICS.h index 34faa9ad31..7ee89a0a45 100644 --- a/Marlin/pins_MINITRONICS.h +++ b/Marlin/pins_MINITRONICS.h @@ -28,82 +28,98 @@ #error "Oops! Make sure you have 'Minitronics' selected from the 'Tools -> Boards' menu." #endif +#if HOTENDS > 2 + #error "Minitronics supports up to 2 hotends. Comment this line to keep going." +#endif + #define BOARD_NAME "Minitronics v1.0 / v1.1" #define LARGE_FLASH true -#define X_STEP_PIN 48 -#define X_DIR_PIN 47 -#define X_ENABLE_PIN 49 -#define X_MIN_PIN 5 -#define X_MAX_PIN 2 +// +// Limit Switches +// +#define X_MIN_PIN 5 +#define X_MAX_PIN 2 +#define Y_MIN_PIN 2 +#define Y_MAX_PIN 15 +#define Z_MIN_PIN 6 +#define Z_MAX_PIN -1 -#define Y_STEP_PIN 39 // A6 -#define Y_DIR_PIN 40 // A0 -#define Y_ENABLE_PIN 38 -#define Y_MIN_PIN 2 -#define Y_MAX_PIN 15 +// +// Steppers +// +#define X_STEP_PIN 48 +#define X_DIR_PIN 47 +#define X_ENABLE_PIN 49 -#define Z_STEP_PIN 42 // A2 -#define Z_DIR_PIN 43 // A6 -#define Z_ENABLE_PIN 41 // A1 -#define Z_MIN_PIN 6 -#define Z_MAX_PIN -1 +#define Y_STEP_PIN 39 // A6 +#define Y_DIR_PIN 40 // A0 +#define Y_ENABLE_PIN 38 -#define E0_STEP_PIN 45 -#define E0_DIR_PIN 44 -#define E0_ENABLE_PIN 27 +#define Z_STEP_PIN 42 // A2 +#define Z_DIR_PIN 43 // A6 +#define Z_ENABLE_PIN 41 // A1 -#define E1_STEP_PIN 36 -#define E1_DIR_PIN 35 -#define E1_ENABLE_PIN 37 +#define E0_STEP_PIN 45 +#define E0_DIR_PIN 44 +#define E0_ENABLE_PIN 27 -#define E2_STEP_PIN -1 -#define E2_DIR_PIN -1 -#define E2_ENABLE_PIN -1 +#define E1_STEP_PIN 36 +#define E1_DIR_PIN 35 +#define E1_ENABLE_PIN 37 -#define SDSS 16 -#define LED_PIN 46 +// +// Temperature Sensors +// +#define TEMP_0_PIN 7 // Analog Input +#define TEMP_1_PIN 6 // Analog Input +#define TEMP_BED_PIN 6 // Analog Input -#define FAN_PIN 9 +// +// Heaters / Fans +// +#define HEATER_0_PIN 7 // EXTRUDER 1 +#define HEATER_1_PIN 8 // EXTRUDER 2 +#define HEATER_BED_PIN 3 // BED -#define TEMP_0_PIN 7 // ANALOG NUMBERING -#define TEMP_1_PIN 6 // ANALOG NUMBERING -#define TEMP_BED_PIN 6 // ANALOG NUMBERING +#define FAN_PIN 9 -#define HEATER_0_PIN 7 // EXTRUDER 1 -#define HEATER_1_PIN 8 // EXTRUDER 2 -#define HEATER_BED_PIN 3 // BED +// +// Misc. Functions +// +#define SDSS 16 +#define LED_PIN 46 -/** - * Controllers and LCDs - */ -#define BEEPER_PIN -1 +// +// LCD / Controller +// +#define BEEPER_PIN -1 #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 15 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 11 // SID (MOSI) - #define LCD_PINS_D4 10 // SCK (CLK) clock + #define LCD_PINS_RS 15 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE 11 // SID (MOSI) + #define LCD_PINS_D4 10 // SCK (CLK) clock - #define BTN_EN1 18 - #define BTN_EN2 17 - #define BTN_ENC 25 + #define BTN_EN1 18 + #define BTN_EN2 17 + #define BTN_ENC 25 - #define SD_DETECT_PIN 30 + #define SD_DETECT_PIN 30 #else - #define LCD_PINS_RS -1 - #define LCD_PINS_ENABLE -1 - #define LCD_PINS_D4 -1 - #define LCD_PINS_D5 -1 - #define LCD_PINS_D6 -1 - #define LCD_PINS_D7 -1 + #define LCD_PINS_RS -1 + #define LCD_PINS_ENABLE -1 + #define LCD_PINS_D4 -1 + #define LCD_PINS_D5 -1 + #define LCD_PINS_D6 -1 + #define LCD_PINS_D7 -1 // Buttons are directly attached using keypad - #define BTN_EN1 -1 - #define BTN_EN2 -1 - #define BTN_ENC -1 + #define BTN_EN1 -1 + #define BTN_EN2 -1 + #define BTN_ENC -1 - #define SD_DETECT_PIN -1 // Minitronics doesn't use this + #define SD_DETECT_PIN -1 // Minitronics doesn't use this #endif diff --git a/Marlin/pins_MKS_13.h b/Marlin/pins_MKS_13.h index 3b5b242ab5..ce1217157c 100644 --- a/Marlin/pins_MKS_13.h +++ b/Marlin/pins_MKS_13.h @@ -35,11 +35,17 @@ #define BOARD_NAME "MKS > v1.3" +// +// Heaters / Fans +// // Power outputs EFBF or EFBE #define MOSFET_D_PIN 7 #include "pins_RAMPS.h" +// +// LCD / Controller +// #if ENABLED(VIKI2) || ENABLED(miniVIKI) /** * VIKI2 Has two groups of wires with... @@ -120,9 +126,9 @@ #define BEEPER_PIN 25 // yellow RED-LED - #define STAT_LED_RED 16 + #define STAT_LED_RED_PIN 16 // white BLUE-LED - #define STAT_LED_BLUE 17 + #define STAT_LED_BLUE_PIN 17 #endif diff --git a/Marlin/pins_MKS_BASE.h b/Marlin/pins_MKS_BASE.h index 8c7222017a..c098341530 100644 --- a/Marlin/pins_MKS_BASE.h +++ b/Marlin/pins_MKS_BASE.h @@ -30,6 +30,9 @@ #define BOARD_NAME "MKS BASE 1.0" +// +// Heaters / Fans +// // Power outputs EFBF or EFBE #define MOSFET_D_PIN 7 diff --git a/Marlin/pins_OMCA.h b/Marlin/pins_OMCA.h index 9ec6309d57..a69d61ec73 100644 --- a/Marlin/pins_OMCA.h +++ b/Marlin/pins_OMCA.h @@ -57,33 +57,32 @@ #define BOARD_NAME "Final OMCA" +// +// Limit Switches +// +#define X_STOP_PIN 0 +#define Y_STOP_PIN 1 +#define Z_STOP_PIN 2 + +// +// Steppers +// #define X_STEP_PIN 26 #define X_DIR_PIN 25 #define X_ENABLE_PIN 10 -#define X_STOP_PIN 0 #define Y_STEP_PIN 28 #define Y_DIR_PIN 27 #define Y_ENABLE_PIN 10 -#define Y_STOP_PIN 1 #define Z_STEP_PIN 23 #define Z_DIR_PIN 22 #define Z_ENABLE_PIN 10 -#define Z_STOP_PIN 2 #define E0_STEP_PIN 24 #define E0_DIR_PIN 21 #define E0_ENABLE_PIN 10 -// future proofing -#define __FS 20 -#define __FD 19 -#define __GS 18 -#define __GD 13 - -#define UNUSED_PWM 14 // PWM on LEFT connector - #define E1_STEP_PIN -1 // 21 #define E1_DIR_PIN -1 // 20 #define E1_ENABLE_PIN -1 // 19 @@ -92,16 +91,33 @@ #define E2_DIR_PIN -1 // 20 #define E2_ENABLE_PIN -1 // 18 -#define SDSS 11 -#define FAN_PIN 14 // PWM on MIDDLE connector +// +// Temperature Sensors +// +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 1 // Analog Input +#define TEMP_BED_PIN 2 // Analog Input (1,2 or I2C) +// +// Heaters / Fans +// #define HEATER_0_PIN 3 // DONE PWM on RIGHT connector #define HEATER_BED_PIN 4 -#define TEMP_0_PIN 0 // ANALOG INPUT NUMBERING -#define TEMP_1_PIN 1 // ANALOG -#define TEMP_BED_PIN 2 // 1,2 or I2C +#define FAN_PIN 14 // PWM on MIDDLE connector + +// +// Misc. Functions +// +#define SDSS 11 #define I2C_SCL 16 #define I2C_SDA 17 +// future proofing +#define __FS 20 +#define __FD 19 +#define __GS 18 +#define __GD 13 + +#define UNUSED_PWM 14 // PWM on LEFT connector diff --git a/Marlin/pins_OMCA_A.h b/Marlin/pins_OMCA_A.h index 39d232aee2..d325a648d9 100644 --- a/Marlin/pins_OMCA_A.h +++ b/Marlin/pins_OMCA_A.h @@ -56,20 +56,27 @@ #define BOARD_NAME "Alpha OMCA" +// +// Limit Switches +// +#define X_STOP_PIN 0 +#define Y_STOP_PIN 1 +#define Z_STOP_PIN 2 + +// +// Steppers +// #define X_STEP_PIN 21 #define X_DIR_PIN 20 #define X_ENABLE_PIN 24 -#define X_STOP_PIN 0 #define Y_STEP_PIN 23 #define Y_DIR_PIN 22 #define Y_ENABLE_PIN 24 -#define Y_STOP_PIN 1 #define Z_STEP_PIN 26 #define Z_DIR_PIN 25 #define Z_ENABLE_PIN 24 -#define Z_STOP_PIN 2 #define E0_STEP_PIN 28 #define E0_DIR_PIN 27 @@ -83,10 +90,21 @@ #define E2_DIR_PIN -1 // 16 #define E2_ENABLE_PIN 24 -#define SDSS 11 +// +// Temperature Sensors +// +#define TEMP_0_PIN 0 // Analog Input (D27) + +// +// Heaters / Fans +// +#define HEATER_0_PIN 4 + #define FAN_PIN 3 -#define HEATER_0_PIN 4 -#define TEMP_0_PIN 0 //D27 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! +// +// Misc. Functions +// +#define SDSS 11 /* Unused (1) (2) (3) 4 5 6 7 8 9 10 11 12 13 (14) (15) (16) 17 (18) (19) (20) (21) (22) (23) 24 (25) (26) (27) 28 (29) (30) (31) */ diff --git a/Marlin/pins_PRINTRBOARD.h b/Marlin/pins_PRINTRBOARD.h index fb1874b643..b53db770a5 100644 --- a/Marlin/pins_PRINTRBOARD.h +++ b/Marlin/pins_PRINTRBOARD.h @@ -36,11 +36,27 @@ #endif #define BOARD_NAME "Printrboard" + +#define USBCON 1286 // Disable MarlinSerial etc. #define LARGE_FLASH true // Disable JTAG pins so they can be used for the Extrudrboard #define DISABLE_JTAG true +// +// Limit Switches +// +#define X_STOP_PIN 35 +#if ENABLED(SDSUPPORT) + #define Y_STOP_PIN 37 // Move Ystop to Estop socket +#else + #define Y_STOP_PIN 8 // Ystop in Ystop socket +#endif +#define Z_STOP_PIN 36 + +// +// Steppers +// #define X_STEP_PIN 0 #define X_DIR_PIN 1 #define X_ENABLE_PIN 39 @@ -57,7 +73,16 @@ #define E0_DIR_PIN 7 #define E0_ENABLE_PIN 19 -#define HEATER_0_PIN 21 // Extruder +// +// Temperature Sensors +// +#define TEMP_0_PIN 1 // Analog Input +#define TEMP_BED_PIN 0 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 21 // Extruder #define HEATER_1_PIN 46 #define HEATER_2_PIN 47 #define HEATER_BED_PIN 20 @@ -70,39 +95,32 @@ #define FAN_PIN 16 #endif -#define X_STOP_PIN 35 -#if ENABLED(SDSUPPORT) - #define Y_STOP_PIN 37 // Move Ystop to Estop socket -#else - #define Y_STOP_PIN 8 // Ystop in Ystop socket -#endif -#define Z_STOP_PIN 36 -#define TEMP_0_PIN 1 // Extruder / Analog pin numbering -#define TEMP_BED_PIN 0 // Bed / Analog pin numbering - -#define FILWIDTH_PIN 2 // ANALOG NUMBERING - -////LCD Pin Setup//// - +// +// Misc. Functions +// #define SDSS 26 +#define FILWIDTH_PIN 2 // Analog Input +// +// LCD / Controller +// #if ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) - //we have no buzzer installed + // we have no buzzer installed #define BEEPER_PIN -1 - //LCD Pins + // LCD Pins #if ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 27 //RX1 - fastio.h pin mapping 27 - #define BTN_EN2 26 //TX1 - fastio.h pin mapping 26 - #define BTN_ENC 43 //A3 - fastio.h pin mapping 43 - #define SDSS 40 //use SD card on Panelolu2 (Teensyduino pin mapping) + #define BTN_EN1 27 // RX1 - fastio.h pin mapping 27 + #define BTN_EN2 26 // TX1 - fastio.h pin mapping 26 + #define BTN_ENC 43 // A3 - fastio.h pin mapping 43 + #define SDSS 40 // use SD card on Panelolu2 (Teensyduino pin mapping) #else #define BTN_EN1 16 #define BTN_EN2 17 - #define BTN_ENC 18//the click + #define BTN_ENC 18 // the click #endif // LCD_I2C_PANELOLU2 - //not connected to a pin + // not connected to a pin #define SD_DETECT_PIN -1 #define LCD_PINS_RS 9 @@ -115,22 +133,22 @@ #endif // ULTRA_LCD && NEWPANEL #if ENABLED(VIKI2) || ENABLED(miniVIKI) - //FastIO + // FastIO #define BEEPER_PIN 32 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 42 //Non-FastIO - #define DOGLCD_CS 43 //Non-FastIO + #define DOGLCD_A0 42 // Non-FastIO + #define DOGLCD_CS 43 // Non-FastIO #define LCD_SCREEN_ROT_180 - //The encoder and click button (FastIO Pins) + // The encoder and click button (FastIO Pins) #define BTN_EN1 26 #define BTN_EN2 27 #define BTN_ENC 47 #define SDSS 45 #define SD_DETECT_PIN -1 // FastIO (Manual says 72 I'm not certain cause I can't test) - #if ENABLED(TEMP_STAT_LEDS) - #define STAT_LED_RED 12 //Non-FastIO - #define STAT_LED_BLUE 10 //Non-FastIO - #endif + + #define STAT_LED_RED_PIN 12 // Non-FastIO + #define STAT_LED_BLUE_PIN 10 // Non-FastIO + #endif diff --git a/Marlin/pins_PRINTRBOARD_REVF.h b/Marlin/pins_PRINTRBOARD_REVF.h index 61b23fb4cd..fa5c3a615a 100644 --- a/Marlin/pins_PRINTRBOARD_REVF.h +++ b/Marlin/pins_PRINTRBOARD_REVF.h @@ -38,6 +38,16 @@ #define BOARD_NAME "Printrboard Rev F" #define LARGE_FLASH true +// +// Limit Switches +// +#define X_STOP_PIN 35 +#define Y_STOP_PIN 12 +#define Z_STOP_PIN 36 + +// +// Steppers +// #define X_STEP_PIN 0 #define X_DIR_PIN 1 #define X_ENABLE_PIN 39 @@ -54,7 +64,28 @@ #define E0_DIR_PIN 7 #define E0_ENABLE_PIN 19 -#define HEATER_0_PIN 21 // Extruder +// uncomment to enable an I2C based DAC like on the Printrboard REVF +#define DAC_STEPPER_CURRENT +// Number of channels available for DAC, For Printrboar REVF there are 4 +#define DAC_STEPPER_ORDER { 3, 2, 1, 0 } + +#define DAC_STEPPER_SENSE 0.11 +#define DAC_STEPPER_ADDRESS 0 +#define DAC_STEPPER_MAX 3520 +#define DAC_STEPPER_VREF 1 // internal Vref, gain 1x = 2.048V +#define DAC_STEPPER_GAIN 0 +#define DAC_OR_ADDRESS 0x00 + +// +// Temperature Sensors +// +#define TEMP_0_PIN 1 // Analog Input (Extruder) +#define TEMP_BED_PIN 0 // Analog Input (Bed) + +// +// Heaters / Fans +// +#define HEATER_0_PIN 21 // Extruder #define HEATER_1_PIN 46 #define HEATER_2_PIN 47 #define HEATER_BED_PIN 20 @@ -67,31 +98,15 @@ #define FAN_PIN 16 #endif -#define X_STOP_PIN 35 -#define Y_STOP_PIN 12 -#define Z_STOP_PIN 36 - -#define TEMP_0_PIN 1 // Extruder / Analog pin numbering -#define TEMP_BED_PIN 0 // Bed / Analog pin numbering - -#define FILWIDTH_PIN 2 // ANALOG NUMBERING - -////LCD Pin Setup//// - +// +// Misc. Functions +// #define SDSS 20 // Teensylu pin mapping +#define FILWIDTH_PIN 2 // Analog Input -// uncomment to enable an I2C based DAC like on the Printrboard REVF -#define DAC_STEPPER_CURRENT -// Number of channels available for DAC, For Printrboar REVF there are 4 -#define DAC_STEPPER_ORDER {3,2,1,0} - -#define DAC_STEPPER_SENSE 0.11 -#define DAC_STEPPER_ADDRESS 0 -#define DAC_STEPPER_MAX 3520 -#define DAC_STEPPER_VREF 1 //internal Vref, gain 1x = 2.048V -#define DAC_STEPPER_GAIN 0 -#define DAC_OR_ADDRESS 0x00 - +// +// LCD / Controller +// #if ENABLED(ULTRA_LCD) #define BEEPER_PIN -1 @@ -104,11 +119,11 @@ #define BTN_EN1 16 #define BTN_EN2 17 - #define BTN_ENC 18//the click + #define BTN_ENC 18 // the click #define SD_DETECT_PIN -1 - //encoder rotation values + // encoder rotation values #define encrot0 0 #define encrot1 2 #define encrot2 3 @@ -116,22 +131,19 @@ #endif #if ENABLED(VIKI2) || ENABLED(miniVIKI) - #define BEEPER_PIN 32 //FastIO - // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 42 //Non-FastIO - #define DOGLCD_CS 43 //Non-FastIO + #define BEEPER_PIN 32 // FastIO + #define DOGLCD_A0 42 // Non-FastIO + #define DOGLCD_CS 43 // Non-FastIO #define LCD_SCREEN_ROT_180 - //The encoder and click button (FastIO Pins) + // (FastIO Pins) #define BTN_EN1 26 #define BTN_EN2 27 #define BTN_ENC 47 #define SDSS 45 - #define SD_DETECT_PIN -1 // FastIO (Manual says 72 I'm not certain cause I can't test) + #define SD_DETECT_PIN -1 // FastIO (Manual says 72) - #if ENABLED(TEMP_STAT_LEDS) - #define STAT_LED_RED 12 //Non-FastIO - #define STAT_LED_BLUE 10 //Non-FastIO - #endif + #define STAT_LED_RED_PIN 12 // Non-FastIO + #define STAT_LED_BLUE_PIN 10 // Non-FastIO #endif diff --git a/Marlin/pins_RAMBO.h b/Marlin/pins_RAMBO.h old mode 100644 new mode 100755 index 278774caf1..8289940752 --- a/Marlin/pins_RAMBO.h +++ b/Marlin/pins_RAMBO.h @@ -20,6 +20,22 @@ * */ +/** + * IMPORTANT NOTE: + * Rambo users should be sure to compile Marlin using either the RAMBo + * board type if using the Arduino IDE - available via the link below - or + * the 'rambo' environment if using platformio, by specifying '-e rambo' on + * the command line or by changing the value of the 'env_default' variable to + * 'rambo' in the supplied platformio.ini. + * + * If you don't compile using the proper board type, the RAMBo's extended + * pins will likely be unavailable and accessories/addons may not work. + * + * Instructions for installing the Arduino RAMBo board type for the + * Arduino IDE are available at: + * http://reprap.org/wiki/Rambo_firmware + */ + /** * Rambo pin assignments */ @@ -32,86 +48,103 @@ #define LARGE_FLASH true -// Servo support -#define SERVO0_PIN 22 // Motor header MX1 -#define SERVO1_PIN 23 // Motor header MX2 -#define SERVO2_PIN 24 // Motor header MX3 -#define SERVO3_PIN 5 // PWM header pin 5 +// +// Servos +// +#define SERVO0_PIN 22 // Motor header MX1 +#define SERVO1_PIN 23 // Motor header MX2 +#define SERVO2_PIN 24 // Motor header MX3 +#define SERVO3_PIN 5 // PWM header pin 5 + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 30 +#endif #if ENABLED(Z_PROBE_SLED) #define SLED_PIN -1 #endif -#define X_MIN_PIN 12 -#define X_MAX_PIN 24 -#define Y_MIN_PIN 11 -#define Y_MAX_PIN 23 -#define Z_MIN_PIN 10 -#define Z_MAX_PIN 30 -#ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 10 -#endif +// +// Limit Switches +// +#define X_MIN_PIN 12 +#define X_MAX_PIN 24 +#define Y_MIN_PIN 11 +#define Y_MAX_PIN 23 +#define Z_MIN_PIN 10 +#define Z_MAX_PIN 30 -#define X_STEP_PIN 37 -#define X_DIR_PIN 48 -#define X_ENABLE_PIN 29 -#define X_MS1_PIN 40 -#define X_MS2_PIN 41 +// +// Steppers +// +#define X_STEP_PIN 37 +#define X_DIR_PIN 48 +#define X_ENABLE_PIN 29 -#define Y_STEP_PIN 36 -#define Y_DIR_PIN 49 -#define Y_ENABLE_PIN 28 -#define Y_MS1_PIN 69 -#define Y_MS2_PIN 39 +#define Y_STEP_PIN 36 +#define Y_DIR_PIN 49 +#define Y_ENABLE_PIN 28 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 47 -#define Z_ENABLE_PIN 27 -#define Z_MS1_PIN 68 -#define Z_MS2_PIN 67 +#define Z_STEP_PIN 35 +#define Z_DIR_PIN 47 +#define Z_ENABLE_PIN 27 -#define HEATER_BED_PIN 3 -#define TEMP_BED_PIN 2 +#define E0_STEP_PIN 34 +#define E0_DIR_PIN 43 +#define E0_ENABLE_PIN 26 -#define HEATER_0_PIN 9 -#define TEMP_0_PIN 0 +#define E1_STEP_PIN 33 +#define E1_DIR_PIN 42 +#define E1_ENABLE_PIN 25 -#define HEATER_1_PIN 7 -#define TEMP_1_PIN 1 +// Microstepping pins - Mapping not from fastio.h (?) +#define X_MS1_PIN 40 +#define X_MS2_PIN 41 +#define Y_MS1_PIN 69 +#define Y_MS2_PIN 39 +#define Z_MS1_PIN 68 +#define Z_MS2_PIN 67 +#define E0_MS1_PIN 65 +#define E0_MS2_PIN 66 +#define E1_MS1_PIN 63 +#define E1_MS2_PIN 64 -#if ENABLED(BARICUDA) - #define HEATER_2_PIN 6 -#endif - -#define E0_STEP_PIN 34 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 26 -#define E0_MS1_PIN 65 -#define E0_MS2_PIN 66 - -#define E1_STEP_PIN 33 -#define E1_DIR_PIN 42 -#define E1_ENABLE_PIN 25 -#define E1_MS1_PIN 63 -#define E1_MS2_PIN 64 - -#define DIGIPOTSS_PIN 38 +#define DIGIPOTSS_PIN 38 #define DIGIPOT_CHANNELS {4,5,3,0,1} // X Y Z E0 E1 digipot channels to stepper driver mapping +// +// Temperature Sensors +// +#define TEMP_0_PIN 0 // Analog Input +#define TEMP_1_PIN 1 // Analog Input +#define TEMP_BED_PIN 2 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 9 +#define HEATER_1_PIN 7 +#define HEATER_2_PIN 6 +#define HEATER_BED_PIN 3 + +#define FAN_PIN 8 +#define FAN1_PIN 6 +#define FAN2_PIN 2 + +// +// Misc. Functions +// #define SDSS 53 #define LED_PIN 13 -#define FAN_PIN 8 - -#define FILWIDTH_PIN 3 // ANALOG NUMBERING - -/********************************************************** - Fan Pins - Fan_0 8 - Fan_1 6 - Fan_2 2 -***********************************************************/ -#define PS_ON_PIN 4 +#define FILWIDTH_PIN 3 // Analog Input +#define PS_ON_PIN 4 +// +// LCD / Controller +// #if ENABLED(ULTRA_LCD) #define KILL_PIN 80 @@ -127,6 +160,9 @@ #if ENABLED(VIKI2) || ENABLED(miniVIKI) #define BEEPER_PIN 44 + // NB: Panucatt's Viki 2.0 wiring diagram (v1.2) indicates that the + // beeper/buzzer is connected to pin 33; however, the pin used in the + // diagram is actually pin 44, so this is correct. #define DOGLCD_A0 70 #define DOGLCD_CS 71 @@ -138,10 +174,8 @@ #define SD_DETECT_PIN -1 // Pin 72 if using easy adapter board - #if ENABLED(TEMP_STAT_LEDS) - #define STAT_LED_RED 22 - #define STAT_LED_BLUE 32 - #endif + #define STAT_LED_RED_PIN 22 + #define STAT_LED_BLUE_PIN 32 #else @@ -156,12 +190,12 @@ #endif // VIKI2/miniVIKI - #else //!NEWPANEL - old style panel with shift register + #else // !NEWPANEL - old style panel with shift register // No Beeper added #define BEEPER_PIN 33 - //buttons are attached to a shift register + // buttons are attached to a shift register // Not wired yet //#define SHIFT_CLK 38 //#define SHIFT_LD 42 @@ -178,4 +212,3 @@ #endif // !NEWPANEL #endif // ULTRA_LCD - diff --git a/Marlin/pins_RAMPS.h b/Marlin/pins_RAMPS.h index 5f2e0d1194..da14a6dab2 100644 --- a/Marlin/pins_RAMPS.h +++ b/Marlin/pins_RAMPS.h @@ -54,6 +54,9 @@ #define LARGE_FLASH true +// +// Servos +// #ifdef IS_RAMPS_13 #define SERVO0_PIN 7 // RAMPS_13 // Will conflict with BTN_EN2 on LCD_I2C_VIKI #else @@ -63,6 +66,9 @@ #define SERVO2_PIN 5 #define SERVO3_PIN 4 +// +// Limit Switches +// #define X_MIN_PIN 3 #ifndef X_MAX_PIN #define X_MAX_PIN 2 @@ -71,49 +77,61 @@ #define Y_MAX_PIN 15 #define Z_MIN_PIN 18 #define Z_MAX_PIN 19 + +// +// Z Probe (when not Z_MIN_PIN) +// #ifndef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN 32 #endif +#define SLED_PIN -1 + +// +// Steppers +// #define X_STEP_PIN 54 #define X_DIR_PIN 55 #define X_ENABLE_PIN 38 +#define X_CS_PIN 53 #define Y_STEP_PIN 60 #define Y_DIR_PIN 61 #define Y_ENABLE_PIN 56 +#define Y_CS_PIN 49 #define Z_STEP_PIN 46 #define Z_DIR_PIN 48 #define Z_ENABLE_PIN 62 +#define Z_CS_PIN 40 #define E0_STEP_PIN 26 #define E0_DIR_PIN 28 #define E0_ENABLE_PIN 24 +#define E0_CS_PIN 42 #define E1_STEP_PIN 36 #define E1_DIR_PIN 34 #define E1_ENABLE_PIN 30 +#define E1_CS_PIN 44 -#define SDSS 53 -#define LED_PIN 13 +// +// Temperature Sensors +// +#define TEMP_0_PIN 13 // Analog Input +#define TEMP_1_PIN 15 // Analog Input +#define TEMP_BED_PIN 14 // Analog Input -// Use the RAMPS 1.4 Analog input 5 on the AUX2 connector -#define FILWIDTH_PIN 5 // ANALOG NUMBERING - -// define digital pin 4 for the filament runout sensor. Use the RAMPS 1.4 digital input 4 on the servos connector -#define FIL_RUNOUT_PIN 4 - -#define PS_ON_PIN 12 -#define TEMP_0_PIN 13 // ANALOG NUMBERING -#define TEMP_1_PIN 15 // ANALOG NUMBERING -#define TEMP_BED_PIN 14 // ANALOG NUMBERING - -#if ENABLED(Z_PROBE_SLED) - #define SLED_PIN -1 +// SPI for Max6675 or Max31855 Thermocouple +#if DISABLED(SDSUPPORT) + #define MAX6675_SS 66 // Do not use pin 53 if there is even the remote possibility of using Display/SD card +#else + #define MAX6675_SS 66 // Do not use pin 49 as this is tied to the switch inside the SD card socket to detect if there is an SD card present #endif +// // Augmentation for auto-assigning RAMPS plugs +// #if DISABLED(IS_RAMPS_EEB) && DISABLED(IS_RAMPS_EEF) && DISABLED(IS_RAMPS_EFB) && DISABLED(IS_RAMPS_EFF) && DISABLED(IS_RAMPS_SF) && !PIN_EXISTS(MOSFET_D) #if HOTENDS > 1 #if TEMP_SENSOR_BED @@ -128,10 +146,9 @@ #endif #endif -/** - * Hi Voltage PWM Pin Assignments - */ - +// +// Heaters / Fans +// #ifndef MOSFET_D_PIN #define MOSFET_D_PIN -1 #endif @@ -159,7 +176,6 @@ #elif ENABLED(IS_RAMPS_EFF) // Hotend, Fan, Fan #define FAN_PIN RAMPS_D9_PIN #define FAN1_PIN RAMPS_D8_PIN - #define CONTROLLERFAN_PIN -1 #elif ENABLED(IS_RAMPS_SF) // Spindle, Fan #define FAN_PIN RAMPS_D8_PIN #else // Non-specific are "EFB" (i.e., "EFBF" or "EFBE") @@ -176,16 +192,29 @@ #define FAN_PIN 4 // IO pin. Buffer needed #endif -/** - * LCD Controller Pin Assignments - */ +// +// Misc. Functions +// +#define SDSS 53 +#define LED_PIN 13 +// Use the RAMPS 1.4 Analog input 5 on the AUX2 connector +#define FILWIDTH_PIN 5 // Analog Input + +// define digital pin 4 for the filament runout sensor. Use the RAMPS 1.4 digital input 4 on the servos connector +#define FIL_RUNOUT_PIN 4 + +#define PS_ON_PIN 12 + +// +// LCD / Controller +// #if ENABLED(ULTRA_LCD) #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 49 //CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 51 //SID (MOSI) - #define LCD_PINS_D4 52 //SCK (CLK) clock + #define LCD_PINS_RS 49 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE 51 // SID (MOSI) + #define LCD_PINS_D4 52 // SCK (CLK) clock #elif ENABLED(NEWPANEL) && ENABLED(PANEL_ONE) #define LCD_PINS_RS 40 #define LCD_PINS_ENABLE 42 @@ -224,7 +253,7 @@ #define KILL_PIN 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) - #define LCD_PIN_BL 39 + #define LCD_BACKLIGHT_PIN 39 #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) @@ -264,10 +293,9 @@ #define KILL_PIN 31 - #if ENABLED(TEMP_STAT_LEDS) - #define STAT_LED_RED 32 - #define STAT_LED_BLUE 35 - #endif + #define STAT_LED_RED_PIN 32 + #define STAT_LED_BLUE_PIN 35 + #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) #define BTN_EN1 35 // reverse if the encoder turns the wrong way. #define BTN_EN2 37 @@ -278,13 +306,13 @@ #define BEEPER_PIN 23 #define DOGLCD_CS 29 #define DOGLCD_A0 27 - #define LCD_PIN_BL 33 + #define LCD_BACKLIGHT_PIN 33 #elif ENABLED(MINIPANEL) #define BEEPER_PIN 42 // Pins for DOGM SPI LCD Support #define DOGLCD_A0 44 #define DOGLCD_CS 66 - #define LCD_PIN_BL 65 // backlight LED on A11/D65 + #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 #define SDSS 53 #define KILL_PIN 64 @@ -294,11 +322,11 @@ //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 - //The encoder and click button + // The encoder and click button #define BTN_EN1 40 #define BTN_EN2 63 #define BTN_ENC 59 - //not connected to a pin + // not connected to a pin #define SD_DETECT_PIN 49 #else @@ -321,24 +349,17 @@ #else #define BTN_EN1 37 #define BTN_EN2 35 - #define BTN_ENC 31 // the click + #define BTN_ENC 31 // the click #endif #if ENABLED(G3D_PANEL) #define SD_DETECT_PIN 49 #define KILL_PIN 41 #else - // #define SD_DETECT_PIN -1 // Ramps doesn't use this + //#define SD_DETECT_PIN -1 // Ramps doesn't use this #endif #endif #endif // NEWPANEL #endif // ULTRA_LCD - -// SPI for Max6675 or Max31855 Thermocouple -#if DISABLED(SDSUPPORT) - #define MAX6675_SS 66 // Do not use pin 53 if there is even the remote possibility of using Display/SD card -#else - #define MAX6675_SS 66 // Do not use pin 49 as this is tied to the switch inside the SD card socket to detect if there is an SD card present -#endif diff --git a/Marlin/pins_RAMPS_OLD.h b/Marlin/pins_RAMPS_OLD.h index 213bd3f1e8..29812bbdf4 100644 --- a/Marlin/pins_RAMPS_OLD.h +++ b/Marlin/pins_RAMPS_OLD.h @@ -33,48 +33,71 @@ // Uncomment the following line for RAMPS v1.0 //#define RAMPS_V_1_0 +// +// Limit Switches +// +#define X_MIN_PIN 3 +#define X_MAX_PIN 2 +#define Y_MIN_PIN 16 +#define Y_MAX_PIN 17 +#define Z_MIN_PIN 18 +#define Z_MAX_PIN 19 + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 19 +#endif + +// +// Steppers +// #define X_STEP_PIN 26 #define X_DIR_PIN 28 #define X_ENABLE_PIN 24 -#define X_MIN_PIN 3 -#define X_MAX_PIN 2 #define Y_STEP_PIN 38 #define Y_DIR_PIN 40 #define Y_ENABLE_PIN 36 -#define Y_MIN_PIN 16 -#define Y_MAX_PIN 17 #define Z_STEP_PIN 44 #define Z_DIR_PIN 46 #define Z_ENABLE_PIN 42 -#define Z_MIN_PIN 18 -#define Z_MAX_PIN 19 #define E0_STEP_PIN 32 #define E0_DIR_PIN 34 #define E0_ENABLE_PIN 30 -#define SDPOWER 48 -#define SDSS 53 -#define LED_PIN 13 - -#if ENABLED(RAMPS_V_1_0) // RAMPS_V_1_0 - #define HEATER_0_PIN 12 // RAMPS 1.0 - #define HEATER_BED_PIN -1 // RAMPS 1.0 - #define FAN_PIN 11 // RAMPS 1.0 -#else // RAMPS_V_1_1 or RAMPS_V_1_2 - #define HEATER_0_PIN 10 // RAMPS 1.1 - #define HEATER_BED_PIN 8 // RAMPS 1.1 - #define FAN_PIN 9 // RAMPS 1.1 -#endif - -#define TEMP_0_PIN 2 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! -#define TEMP_BED_PIN 1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! +// +// Temperature Sensors +// +#define TEMP_0_PIN 2 // Analog Input +#define TEMP_BED_PIN 1 // Analog Input // SPI for Max6675 or Max31855 Thermocouple #if DISABLED(SDSUPPORT) - #define MAX6675_SS 66// Do not use pin 53 if there is even the remote possibility of using Display/SD card + #define MAX6675_SS 66 // Do not use pin 53 if there is even the remote possibility of using Display/SD card #else - #define MAX6675_SS 66// Do not use pin 49 as this is tied to the switch inside the SD card socket to detect if there is an SD card present + #define MAX6675_SS 66 // Do not use pin 49 as this is tied to the switch inside the SD card socket to detect if there is an SD card present #endif + +// +// Heaters / Fans +// +#if ENABLED(RAMPS_V_1_0) + #define HEATER_0_PIN 12 + #define HEATER_BED_PIN -1 + #define FAN_PIN 11 +#else // RAMPS_V_1_1 or RAMPS_V_1_2 + #define HEATER_0_PIN 10 + #define HEATER_BED_PIN 8 + #define FAN_PIN 9 +#endif + +// +// Misc. Functions +// +#define SDPOWER 48 +#define SDSS 53 +#define LED_PIN 13 diff --git a/Marlin/pins_RIGIDBOARD.h b/Marlin/pins_RIGIDBOARD.h index a60e492ac0..bcd1437c01 100644 --- a/Marlin/pins_RIGIDBOARD.h +++ b/Marlin/pins_RIGIDBOARD.h @@ -26,21 +26,75 @@ #define BOARD_NAME "RigidBoard" -#define RAMPS_D10_PIN 9 // EXTRUDER 1 -#define MOSFET_D_PIN 12 // EXTRUDER 2 or FAN +// +// Z Probe (when not Z_MIN_PIN) +// #ifndef Z_MIN_PROBE_PIN #define Z_MIN_PROBE_PIN 19 // Z-MAX pin J14 End Stops #endif #include "pins_RAMPS.h" +// +// Steppers +// +// RigidBot swaps E0 / E1 plugs vs RAMPS 1.3 +#undef E0_STEP_PIN +#undef E0_DIR_PIN +#undef E0_ENABLE_PIN +#define E0_STEP_PIN 36 +#define E0_DIR_PIN 34 +#define E0_ENABLE_PIN 30 + +#undef E1_STEP_PIN +#undef E1_DIR_PIN +#undef E1_ENABLE_PIN +#define E1_STEP_PIN 26 +#define E1_DIR_PIN 28 +#define E1_ENABLE_PIN 24 + +#define STEPPER_RESET_PIN 41 // Stepper drivers have a reset on RigidBot + +// +// Temperature Sensors +// #undef TEMP_0_PIN #undef TEMP_1_PIN -#define TEMP_0_PIN 14 // ANALOG NUMBERING -#define TEMP_1_PIN 13 // ANALOG NUMBERING +#undef TEMP_BED_PIN +#define TEMP_0_PIN 14 // Analog Input +#define TEMP_1_PIN 13 // Analog Input +#define TEMP_BED_PIN 15 // Analog Input +// SPI for Max6675 or Max31855 Thermocouple +#undef MAX6675_SS +#if DISABLED(SDSUPPORT) + #define MAX6675_SS 53 // Don't use pin 53 if there is even the remote possibility of using Display/SD card +#else + #define MAX6675_SS 49 // Don't use pin 49 as this is tied to the switch inside the SD card socket to detect if there is an SD card present +#endif + +// +// Heaters / Fans +// +#define RAMPS_D10_PIN 9 // EXTRUDER 1 +#define MOSFET_D_PIN 12 // EXTRUDER 2 or FAN + +#undef HEATER_BED_PIN +#define HEATER_BED_PIN 10 + +#undef FAN_PIN +#define FAN_PIN 8 // Same as RAMPS_13_EEF + +// +// Misc. Functions +// +#undef PS_ON_PIN +#define PS_ON_PIN -1 + +// +// LCD / Controller +// // LCD Panel options for the RigidBoard - #if ENABLED(RIGIDBOT_PANEL) #undef BEEPER_PIN @@ -77,41 +131,3 @@ #define KILL_PIN 32 #endif - -// SPI for Max6675 or Max31855 Thermocouple -#undef MAX6675_SS -#if ENABLED(SDSUPPORT) - #define MAX6675_SS 49 // Don't use pin 49 as this is tied to the switch inside the SD card socket to detect if there is an SD card present -#else - #define MAX6675_SS 53 // Don't use pin 53 if there is even the remote possibility of using Display/SD card -#endif - -// RigidBot swaps E0 / E1 plugs vs RAMPS 1.3 - -#undef E0_STEP_PIN -#undef E0_DIR_PIN -#undef E0_ENABLE_PIN -#define E0_STEP_PIN 36 -#define E0_DIR_PIN 34 -#define E0_ENABLE_PIN 30 - -#undef E1_STEP_PIN -#undef E1_DIR_PIN -#undef E1_ENABLE_PIN -#define E1_STEP_PIN 26 -#define E1_DIR_PIN 28 -#define E1_ENABLE_PIN 24 - -#undef FAN_PIN -#define FAN_PIN 8 // Same as RAMPS_13_EEF - -#undef PS_ON_PIN -#define PS_ON_PIN -1 - -#undef HEATER_BED_PIN -#define HEATER_BED_PIN 10 - -#undef TEMP_BED_PIN -#define TEMP_BED_PIN 15 // ANALOG NUMBERING - -#define STEPPER_RESET_PIN 41 // Stepper drivers have a reset on RigidBot diff --git a/Marlin/pins_RIGIDBOARD_V2.h b/Marlin/pins_RIGIDBOARD_V2.h index 7aad12e9ac..501bcc285c 100644 --- a/Marlin/pins_RIGIDBOARD_V2.h +++ b/Marlin/pins_RIGIDBOARD_V2.h @@ -29,15 +29,18 @@ #undef BOARD_NAME #define BOARD_NAME "RigidBoard V2" +// +// Steppers +// // I2C based DAC like on the Printrboard REVF #define DAC_STEPPER_CURRENT // Channels available for DAC, For Rigidboard there are 4 -#define DAC_STEPPER_ORDER {0,1,2,3} +#define DAC_STEPPER_ORDER { 0, 1, 2, 3 } -#define DAC_STEPPER_SENSE 0.11 +#define DAC_STEPPER_SENSE 0.05 // sense resistors on rigidboard stepper chips are .05 value #define DAC_STEPPER_ADDRESS 0 -#define DAC_STEPPER_MAX 5000 -#define DAC_STEPPER_VREF 1 //internal Vref, gain 1x = 2.048V -#define DAC_STEPPER_GAIN 0 -#define DAC_DISABLE_PIN 42 // set low to enable DAC +#define DAC_STEPPER_MAX 4096 // was 5000 but max allowable value is actually 4096 +#define DAC_STEPPER_VREF 1 // internal Vref, gain 2x = 4.096V +#define DAC_STEPPER_GAIN 1 // value of 1 here sets gain of 2 +#define DAC_DISABLE_PIN 42 // set low to enable DAC #define DAC_OR_ADDRESS 0x01 diff --git a/Marlin/pins_RUMBA.h b/Marlin/pins_RUMBA.h index ec5e0236e6..dcc5bee2e0 100644 --- a/Marlin/pins_RUMBA.h +++ b/Marlin/pins_RUMBA.h @@ -35,27 +35,42 @@ #define DEFAULT_MACHINE_NAME "Rumba" #define BOARD_NAME "Rumba" +// +// Servos +// +#define SERVO0_PIN 5 + +// +// Limit Switches +// +#define X_MIN_PIN 37 +#define X_MAX_PIN 36 +#define Y_MIN_PIN 35 +#define Y_MAX_PIN 34 +#define Z_MIN_PIN 33 +#define Z_MAX_PIN 32 + +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 32 +#endif + +// +// Steppers +// #define X_STEP_PIN 17 #define X_DIR_PIN 16 #define X_ENABLE_PIN 48 -#define X_MIN_PIN 37 -#define X_MAX_PIN 36 #define Y_STEP_PIN 54 #define Y_DIR_PIN 47 #define Y_ENABLE_PIN 55 -#define Y_MIN_PIN 35 -#define Y_MAX_PIN 34 #define Z_STEP_PIN 57 #define Z_DIR_PIN 56 #define Z_ENABLE_PIN 62 -#define Z_MIN_PIN 33 -#define Z_MAX_PIN 32 - -#ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 33 -#endif #define E0_STEP_PIN 23 #define E0_DIR_PIN 22 @@ -69,47 +84,59 @@ #define E2_DIR_PIN 28 #define E2_ENABLE_PIN 39 -#define LED_PIN 13 +// +// Temperature Sensors +// +#if TEMP_SENSOR_0 == -1 + #define TEMP_0_PIN 6 // Analog Input (connector *K1* on RUMBA thermocouple ADD ON is used) +#else + #define TEMP_0_PIN 15 // Analog Input (default connector for thermistor *T0* on rumba board is used) +#endif + +#if TEMP_SENSOR_1 == -1 + #define TEMP_1_PIN 5 // Analog Input (connector *K2* on RUMBA thermocouple ADD ON is used) +#else + #define TEMP_1_PIN 14 // Analog Input (default connector for thermistor *T1* on rumba board is used) +#endif + +#if TEMP_SENSOR_2 == -1 + #define TEMP_2_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can not be used when TEMP_SENSOR_BED is defined as thermocouple) +#else + #define TEMP_2_PIN 13 // Analog Input (default connector for thermistor *T2* on rumba board is used) +#endif + +// optional for extruder 4 or chamber: +//#define TEMP_X_PIN 12 // Analog Input (default connector for thermistor *T3* on rumba board is used) + +#if TEMP_SENSOR_BED == -1 + #define TEMP_BED_PIN 7 // Analog Input (connector *K3* on RUMBA thermocouple ADD ON is used <-- this can not be used when TEMP_SENSOR_2 is defined as thermocouple) +#else + #define TEMP_BED_PIN 11 // Analog Input (default connector for thermistor *THB* on rumba board is used) +#endif + +// +// Heaters / Fans +// +#define HEATER_0_PIN 2 +#define HEATER_1_PIN 3 +#define HEATER_2_PIN 6 +#define HEATER_3_PIN 8 +#define HEATER_BED_PIN 9 #define FAN_PIN 7 #define FAN1_PIN 8 +// +// Misc. Functions +// +#define SDSS 53 +#define LED_PIN 13 #define PS_ON_PIN 45 #define KILL_PIN 46 -#define HEATER_0_PIN 2 // EXTRUDER 1 -#define HEATER_1_PIN 3 // EXTRUDER 2 -#define HEATER_2_PIN 6 // EXTRUDER 3 - -#if TEMP_SENSOR_0 == -1 - #define TEMP_0_PIN 6 // ANALOG NUMBERING - connector *K1* on RUMBA thermocouple ADD ON is used -#else - #define TEMP_0_PIN 15 // ANALOG NUMBERING - default connector for thermistor *T0* on rumba board is used -#endif - -#if TEMP_SENSOR_1 == -1 - #define TEMP_1_PIN 5 // ANALOG NUMBERING - connector *K2* on RUMBA thermocouple ADD ON is used -#else - #define TEMP_1_PIN 14 // ANALOG NUMBERING - default connector for thermistor *T1* on rumba board is used -#endif - -#if TEMP_SENSOR_2 == -1 - #define TEMP_2_PIN 7 // ANALOG NUMBERING - connector *K3* on RUMBA thermocouple ADD ON is used <-- this can not be used when TEMP_SENSOR_BED is defined as thermocouple -#else - #define TEMP_2_PIN 13 // ANALOG NUMBERING - default connector for thermistor *T2* on rumba board is used -#endif - -//optional for extruder 4 or chamber: #define TEMP_X_PIN 12 // ANALOG NUMBERING - default connector for thermistor *T3* on rumba board is used -//optional FAN1 can be used as 4th heater output: #define HEATER_3_PIN 8 // EXTRUDER 4 - -#define HEATER_BED_PIN 9 // BED -#if TEMP_SENSOR_BED == -1 - #define TEMP_BED_PIN 7 // ANALOG NUMBERING - connector *K3* on RUMBA thermocouple ADD ON is used <-- this can not be used when TEMP_SENSOR_2 is defined as thermocouple -#else - #define TEMP_BED_PIN 11 // ANALOG NUMBERING - default connector for thermistor *THB* on rumba board is used -#endif - -#define SDSS 53 +// +// LCD / Controller +// #define SD_DETECT_PIN 49 #define BEEPER_PIN 44 #define LCD_PINS_RS 19 @@ -121,6 +148,3 @@ #define BTN_EN1 11 #define BTN_EN2 12 #define BTN_ENC 43 - -#define SERVO0_PIN 5 - diff --git a/Marlin/pins_SAINSMART_2IN1.h b/Marlin/pins_SAINSMART_2IN1.h index 8d272ada4a..b418308da8 100644 --- a/Marlin/pins_SAINSMART_2IN1.h +++ b/Marlin/pins_SAINSMART_2IN1.h @@ -30,6 +30,9 @@ #define BOARD_NAME "Sainsmart" +// +// Heaters / Fans +// #define RAMPS_D10_PIN 9 // E #define RAMPS_D9_PIN 7 // F PART FAN in front of board next to Extruder heat // RAMPS_D8_PIN 8 // B diff --git a/Marlin/pins_SANGUINOLOLU_11.h b/Marlin/pins_SANGUINOLOLU_11.h index a6220c596a..cd8d1ccda6 100644 --- a/Marlin/pins_SANGUINOLOLU_11.h +++ b/Marlin/pins_SANGUINOLOLU_11.h @@ -34,35 +34,44 @@ #define IS_MELZI (MB(MELZI) || MB(MELZI_MAKR3D)) -#define X_STEP_PIN 15 -#define X_DIR_PIN 21 +// +// Limit Switches +// #define X_STOP_PIN 18 - -#define Y_STEP_PIN 22 -#define Y_DIR_PIN 23 #define Y_STOP_PIN 19 - -#define Z_STEP_PIN 3 -#define Z_DIR_PIN 2 #define Z_STOP_PIN 20 -#define E0_STEP_PIN 1 -#define E0_DIR_PIN 0 - -#if MB(AZTEEG_X1) || MB(STB_11) || IS_MELZI - #define FAN_PIN 4 // Works for Panelolu2 too -#endif - -#if IS_MELZI - #define LED_PIN 27 // On some broken versions of the Sanguino libraries the pin definitions are wrong, so LED_PIN needs to be 28. But you should upgrade your Sanguino libraries! See #368. -#elif MB(STB_11) - #define LCD_PIN_BL 17 // LCD backlight LED -#endif - +// +// Z Probe (when not Z_MIN_PIN) +// #if ENABLED(Z_PROBE_SLED) #define SLED_PIN -1 #endif +// +// Steppers +// +#define X_STEP_PIN 15 +#define X_DIR_PIN 21 + +#define Y_STEP_PIN 22 +#define Y_DIR_PIN 23 + +#define Z_STEP_PIN 3 +#define Z_DIR_PIN 2 + +#define E0_STEP_PIN 1 +#define E0_DIR_PIN 0 + +// +// Temperature Sensors +// +#define TEMP_0_PIN 7 // Analog Input (pin 33 extruder) +#define TEMP_BED_PIN 6 // Analog Input (pin 34 bed) + +// +// Heaters / Fans +// #define HEATER_0_PIN 13 // (extruder) #if ENABLED(SANGUINOLOLU_V_1_2) @@ -79,7 +88,7 @@ #else - #define HEATER_BED_PIN 14 // (bed) + #define HEATER_BED_PIN 14 // (bed) #define X_ENABLE_PIN -1 #define Y_ENABLE_PIN -1 #define Z_ENABLE_PIN -1 @@ -87,16 +96,29 @@ #endif -#define TEMP_0_PIN 7 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder) -#define TEMP_BED_PIN 6 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed) -#define SDSS 31 +#if MB(AZTEEG_X1) || MB(STB_11) || IS_MELZI + #define FAN_PIN 4 // Works for Panelolu2 too +#endif +// +// Misc. Functions +// /** * On some broken versions of the Sanguino libraries the pin definitions are wrong, * which then needs SDSS as pin 24. But you should upgrade your Sanguino libraries! See #368. */ //#define SDSS 24 +#define SDSS 31 +#if IS_MELZI + #define LED_PIN 27 // On some broken versions of the Sanguino libraries the pin definitions are wrong, so LED_PIN needs to be 28. But you should upgrade your Sanguino libraries! See #368. +#elif MB(STB_11) + #define LCD_BACKLIGHT_PIN 17 // LCD backlight LED +#endif + +// +// LCD / Controller +// #if ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) // No buzzer installed @@ -105,12 +127,12 @@ // LCD Pins #if ENABLED(DOGLCD) - #if ENABLED(U8GLIB_ST7920) //SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 + #if ENABLED(U8GLIB_ST7920) // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 #if IS_MELZI // Melzi board - #define LCD_PINS_RS 30 //CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 29 //SID (MOSI) - #define LCD_PINS_D4 17 //SCK (CLK) clock + #define LCD_PINS_RS 30 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE 29 // SID (MOSI) + #define LCD_PINS_D4 17 // SCK (CLK) clock // Pin 27 is taken by LED_PIN, but Melzi LED does nothing with // Marlin so this can be used for BEEPER_PIN. You can use this pin // with M42 instead of BEEPER_PIN. @@ -162,7 +184,7 @@ #else #define BTN_ENC 16 #define LCD_SDSS 28 // Smart Controller SD card reader rather than the Melzi - #endif //Panelolu2 + #endif // Panelolu2 #define SD_DETECT_PIN -1 @@ -173,7 +195,7 @@ // Pins for DOGM SPI LCD Support #define DOGLCD_A0 30 #define DOGLCD_CS 17 - #define LCD_PIN_BL 28 // backlight LED on PA3 + #define LCD_BACKLIGHT_PIN 28 // backlight LED on PA3 // GLCD features #define LCD_CONTRAST 1 // Uncomment screen orientation diff --git a/Marlin/pins_SAV_MKI.h b/Marlin/pins_SAV_MKI.h index 530f63ada1..c2ad006317 100644 --- a/Marlin/pins_SAV_MKI.h +++ b/Marlin/pins_SAV_MKI.h @@ -35,8 +35,25 @@ #define DEFAULT_SOURCE_CODE_URL "https://github.com/fmalpartida/Marlin/tree/SAV-MkI-config" #define BOARD_NAME "SAV MkI" +#define USBCON 1286 // Disable MarlinSerial etc. #define LARGE_FLASH true +// +// Servos +// +#define SERVO0_PIN 41 // In teensy's pin definition for pinMode (in servo.cpp) + +// +// Limit Switches +// +#define X_STOP_PIN 13 +#define Y_STOP_PIN 14 +//#define Z_STOP_PIN 15 +#define Z_STOP_PIN 36 // For inductive sensor. + +// +// Steppers +// #define X_STEP_PIN 0 #define X_DIR_PIN 1 #define X_ENABLE_PIN 39 @@ -53,19 +70,25 @@ #define E0_DIR_PIN 7 #define E0_ENABLE_PIN 19 +// +// Temperature Sensors +// +#define TEMP_0_PIN 7 // Analog Input (Extruder) +#define TEMP_BED_PIN 6 // Analog Input (Bed) + +// +// Heaters / Fans +// #define HEATER_0_PIN 21 // Extruder #define HEATER_BED_PIN 20 // Bed -#define FAN_PIN 16 // Fan -- from Teensyduino environment. + +#define FAN_PIN 16 // Fan -- from Teensyduino environment. // For the fan and Teensyduino uses a different pin mapping. -#define X_STOP_PIN 13 -#define Y_STOP_PIN 14 -//#define Z_STOP_PIN 15 -#define Z_STOP_PIN 36 // For inductive sensor. -#define TEMP_0_PIN 7 // Extruder / Analog pin numbering -#define TEMP_BED_PIN 6 // Bed / Analog pin numbering - -#define SDSS 20 // PB0 - 8 in marlin env. +// +// Misc. Functions +// +#define SDSS 20 // PB0 - 8 in marlin env. // Extension header pin mapping // ---------------------------- @@ -93,6 +116,9 @@ #define EXT_AUX_A4_IO 44 // Digital IO, 42 (teensy), 44 (marlin) +// +// LCD / Controller +// #define BEEPER_PIN -1 #define LCD_PINS_RS -1 #define LCD_PINS_ENABLE -1 @@ -115,5 +141,3 @@ #define KILL_PIN EXT_AUX_A2_IO #define HOME_PIN EXT_AUX_A4_IO #endif // SAV_3DLCD || SAV_3DGLCD - -#define SERVO0_PIN 41 // In teensy's pin definition for pinMode (in servo.cpp) diff --git a/Marlin/pins_SETHI.h b/Marlin/pins_SETHI.h index ff154acf54..12521f40a1 100644 --- a/Marlin/pins_SETHI.h +++ b/Marlin/pins_SETHI.h @@ -34,53 +34,65 @@ #define GEN7_VERSION 12 // v1.x #endif -//x axis pins -#define X_STEP_PIN 19 -#define X_DIR_PIN 18 -#define X_ENABLE_PIN 24 -#define X_STOP_PIN 2 +// +// Limit Switches +// +#define X_STOP_PIN 2 +#define Y_STOP_PIN 0 +#define Z_MIN_PIN 1 +#define Z_MAX_PIN 0 -//y axis pins -#define Y_STEP_PIN 23 -#define Y_DIR_PIN 22 -#define Y_ENABLE_PIN 24 -#define Y_STOP_PIN 0 +// +// Steppers +// +#define X_STEP_PIN 19 +#define X_DIR_PIN 18 +#define X_ENABLE_PIN 24 -//z axis pins -#define Z_STEP_PIN 26 -#define Z_DIR_PIN 25 -#define Z_ENABLE_PIN 24 -#define Z_MIN_PIN 1 -#define Z_MAX_PIN 0 +#define Y_STEP_PIN 23 +#define Y_DIR_PIN 22 +#define Y_ENABLE_PIN 24 -//extruder pins -#define E0_STEP_PIN 28 -#define E0_DIR_PIN 27 -#define E0_ENABLE_PIN 24 +#define Z_STEP_PIN 26 +#define Z_DIR_PIN 25 +#define Z_ENABLE_PIN 24 -#define TEMP_0_PIN 1 -#define TEMP_BED_PIN 2 +#define E0_STEP_PIN 28 +#define E0_DIR_PIN 27 +#define E0_ENABLE_PIN 24 -#define HEATER_0_PIN 4 -#define HEATER_BED_PIN 3 +// +// Temperature Sensors +// +#define TEMP_0_PIN 1 // Analog Input +#define TEMP_BED_PIN 2 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 4 +#define HEATER_BED_PIN 3 #if (GEN7_VERSION >= 13) // Gen7 v1.3 removed the fan pin - #define FAN_PIN -1 + #define FAN_PIN -1 #else - #define FAN_PIN 31 + #define FAN_PIN 31 #endif -#define PS_ON_PIN 15 +// +// Misc. Functions +// +#define PS_ON_PIN 15 -//All these generations of Gen7 supply thermistor power -//via PS_ON, so ignore bad thermistor readings +// All these generations of Gen7 supply thermistor power +// via PS_ON, so ignore bad thermistor readings #define BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE -//our pin for debugging. -#define DEBUG_PIN 0 +// our pin for debugging. +#define DEBUG_PIN 0 -//our RS485 pins -#define TX_ENABLE_PIN 12 -#define RX_ENABLE_PIN 13 +// our RS485 pins +#define TX_ENABLE_PIN 12 +#define RX_ENABLE_PIN 13 diff --git a/Marlin/pins_TEENSY2.h b/Marlin/pins_TEENSY2.h index f4f7d4c013..b7cf484be3 100644 --- a/Marlin/pins_TEENSY2.h +++ b/Marlin/pins_TEENSY2.h @@ -69,46 +69,65 @@ #error "Oops! Make sure you have 'Teensy++ 2.0' selected from the 'Tools -> Boards' menu." #endif -#ifndef AT90USBxx_TEENSYPP_ASSIGNMENTS // use Teensyduino Teensy++2.0 pin assignments instead of Marlin alphabetical. +#if DISABLED(AT90USBxx_TEENSYPP_ASSIGNMENTS) // use Teensyduino Teensy++2.0 pin assignments instead of Marlin alphabetical. #error "Uncomment #define AT90USBxx_TEENSYPP_ASSIGNMENTS in fastio.h for this config" // (or build from command line) #endif #define BOARD_NAME "Teensy++2.0" +#define USBCON 1286 // Disable MarlinSerial etc. #define LARGE_FLASH true -#define X_STEP_PIN 28 // 0 Marlin -#define X_DIR_PIN 29 // 1 Marlin -#define X_ENABLE_PIN 26 - -#define Y_STEP_PIN 30 // 2 Marlin -#define Y_DIR_PIN 31 // 3 -#define Y_ENABLE_PIN 26 // Shared w/x - -#define Z_STEP_PIN 32 // 4 -#define Z_DIR_PIN 33 // 5 -#define Z_ENABLE_PIN 26 // Shared w/x - -#define E0_STEP_PIN 34 // 6 -#define E0_DIR_PIN 35 // 7 -#define E0_ENABLE_PIN 26 // Shared w/x - -#define HEATER_0_PIN 15 // 21 // Extruder -#define HEATER_BED_PIN 14 // 20 // Bed -#define FAN_PIN 16 // 22 // Fan - +// +// Limit Switches +// #define X_STOP_PIN 2 #define Y_STOP_PIN 3 #define Z_STOP_PIN 4 -#define TEMP_0_PIN 7 // Extruder / Analog pin numbering -#define TEMP_BED_PIN 6 // Bed / Analog pin numbering +// +// Steppers +// +#define X_STEP_PIN 28 // 0 Marlin +#define X_DIR_PIN 29 // 1 Marlin +#define X_ENABLE_PIN 26 +#define Y_STEP_PIN 30 // 2 Marlin +#define Y_DIR_PIN 31 // 3 +#define Y_ENABLE_PIN 26 // Shared w/x + +#define Z_STEP_PIN 32 // 4 +#define Z_DIR_PIN 33 // 5 +#define Z_ENABLE_PIN 26 // Shared w/x + +#define E0_STEP_PIN 34 // 6 +#define E0_DIR_PIN 35 // 7 +#define E0_ENABLE_PIN 26 // Shared w/x + +// +// Temperature Sensors +// +#define TEMP_0_PIN 7 // Analog Input (Extruder) +#define TEMP_BED_PIN 6 // Analog Input (Bed) + +// +// Heaters / Fans +// +#define HEATER_0_PIN 15 // 21 // Extruder +#define HEATER_BED_PIN 14 // 20 // Bed +#define FAN_PIN 16 // 22 // Fan + +// +// Misc. Functions +// #define SDSS 20 // 8 #define LED_PIN 6 #define PS_ON_PIN 27 +// +// LCD / Controller +// #if ENABLED(ULTIPANEL) #define LCD_PINS_RS 8 #define LCD_PINS_ENABLE 9 diff --git a/Marlin/pins_TEENSYLU.h b/Marlin/pins_TEENSYLU.h index 775837767d..b0fc8aec5f 100644 --- a/Marlin/pins_TEENSYLU.h +++ b/Marlin/pins_TEENSYLU.h @@ -37,8 +37,19 @@ #define BOARD_NAME "Teensylu" +#define USBCON 1286 // Disable MarlinSerial etc. #define LARGE_FLASH true +// +// Limit Switches +// +#define X_STOP_PIN 13 +#define Y_STOP_PIN 14 +#define Z_STOP_PIN 15 + +// +// Steppers +// #define X_STEP_PIN 0 #define X_DIR_PIN 1 #define X_ENABLE_PIN 39 @@ -55,6 +66,15 @@ #define E0_DIR_PIN 7 #define E0_ENABLE_PIN 19 +// +// Temperature Sensors +// +#define TEMP_0_PIN 7 // Analog Input (Extruder) +#define TEMP_BED_PIN 6 // Analog Input (Bed) + +// +// Heaters / Fans +// #define HEATER_0_PIN 21 // Extruder #define HEATER_1_PIN 46 #define HEATER_2_PIN 47 @@ -68,23 +88,23 @@ #define FAN_PIN 16 #endif -#define X_STOP_PIN 13 -#define Y_STOP_PIN 14 -#define Z_STOP_PIN 15 -#define TEMP_0_PIN 7 // Extruder / Analog pin numbering -#define TEMP_BED_PIN 6 // Bed / Analog pin numbering - +// +// Misc. Functions +// #define SDSS 8 +// +// LCD / Controller +// #if ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) #define BEEPER_PIN -1 #if ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 27 //RX1 - fastio.h pin mapping 27 - #define BTN_EN2 26 //TX1 - fastio.h pin mapping 26 - #define BTN_ENC 43 //A3 - fastio.h pin mapping 43 - #define SDSS 40 //use SD card on Panelolu2 (Teensyduino pin mapping) + #define BTN_EN1 27 // RX1 - fastio.h pin mapping 27 + #define BTN_EN2 26 // TX1 - fastio.h pin mapping 26 + #define BTN_ENC 43 // A3 - fastio.h pin mapping 43 + #define SDSS 40 // use SD card on Panelolu2 (Teensyduino pin mapping) #endif // LCD_I2C_PANELOLU2 #define SD_DETECT_PIN -1 diff --git a/Marlin/pins_ULTIMAIN_2.h b/Marlin/pins_ULTIMAIN_2.h index c2de0a426a..731f6f88fe 100644 --- a/Marlin/pins_ULTIMAIN_2.h +++ b/Marlin/pins_ULTIMAIN_2.h @@ -32,63 +32,81 @@ #define DEFAULT_SOURCE_CODE_URL "https://github.com/Ultimaker/Marlin" #define BOARD_NAME "Ultimaker 2.x" -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_STOP_PIN 22 -#define X_ENABLE_PIN 27 +// +// Limit Switches +// +#define X_STOP_PIN 22 +#define Y_STOP_PIN 26 +#define Z_STOP_PIN 29 -#define Y_STEP_PIN 32 -#define Y_DIR_PIN 33 -#define Y_STOP_PIN 26 -#define Y_ENABLE_PIN 31 +// +// Steppers +// +#define X_STEP_PIN 25 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 27 -#define Z_STEP_PIN 35 -#define Z_DIR_PIN 36 -#define Z_STOP_PIN 29 -#define Z_ENABLE_PIN 34 +#define Y_STEP_PIN 32 +#define Y_DIR_PIN 33 +#define Y_ENABLE_PIN 31 -#define HEATER_BED_PIN 4 -#define TEMP_BED_PIN 10 +#define Z_STEP_PIN 35 +#define Z_DIR_PIN 36 +#define Z_ENABLE_PIN 34 -#define HEATER_0_PIN 2 -#define TEMP_0_PIN 8 +#define E0_STEP_PIN 42 +#define E0_DIR_PIN 43 +#define E0_ENABLE_PIN 37 -#define HEATER_1_PIN 3 -#define TEMP_1_PIN 9 - -#define E0_STEP_PIN 42 -#define E0_DIR_PIN 43 -#define E0_ENABLE_PIN 37 - -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 - -#define SDSS 53 -#define LED_PIN 8 -#define FAN_PIN 7 -#define SAFETY_TRIGGERED_PIN 28 //PIN to detect the safety circuit has triggered -#define MAIN_VOLTAGE_MEASURE_PIN 14 //Analogue PIN to measure the main voltage, with a 100k - 4k7 resitor divider. +#define E1_STEP_PIN 49 +#define E1_DIR_PIN 47 +#define E1_ENABLE_PIN 48 #define MOTOR_CURRENT_PWM_XY_PIN 44 #define MOTOR_CURRENT_PWM_Z_PIN 45 #define MOTOR_CURRENT_PWM_E_PIN 46 -//Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range +// Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range #define MOTOR_CURRENT_PWM_RANGE 2000 #define DEFAULT_PWM_MOTOR_CURRENT {1300, 1300, 1250} -#define BEEPER_PIN 18 +// +// Temperature Sensors +// +#define TEMP_0_PIN 8 // Analog Input +#define TEMP_1_PIN 9 // Analog Input +#define TEMP_BED_PIN 10 // Analog Input -#define LCD_PINS_RS 20 -#define LCD_PINS_ENABLE 15 -#define LCD_PINS_D4 14 -#define LCD_PINS_D5 21 -#define LCD_PINS_D6 5 -#define LCD_PINS_D7 6 +// +// Heaters / Fans +// +#define HEATER_0_PIN 2 +#define HEATER_1_PIN 3 +#define HEATER_BED_PIN 4 -//buttons are directly attached -#define BTN_EN1 40 -#define BTN_EN2 41 -#define BTN_ENC 19 +#define FAN_PIN 7 -#define SD_DETECT_PIN 39 +// +// Misc. Functions +// +#define SDSS 53 +#define SD_DETECT_PIN 39 +#define LED_PIN 8 +#define SAFETY_TRIGGERED_PIN 28 // PIN to detect the safety circuit has triggered +#define MAIN_VOLTAGE_MEASURE_PIN 14 // ANALOG PIN to measure the main voltage, with a 100k - 4k7 resitor divider. + +// +// LCD / Controller +// +#define BEEPER_PIN 18 + +#define LCD_PINS_RS 20 +#define LCD_PINS_ENABLE 15 +#define LCD_PINS_D4 14 +#define LCD_PINS_D5 21 +#define LCD_PINS_D6 5 +#define LCD_PINS_D7 6 + +// Buttons are directly attached +#define BTN_EN1 40 +#define BTN_EN2 41 +#define BTN_ENC 19 diff --git a/Marlin/pins_ULTIMAKER.h b/Marlin/pins_ULTIMAKER.h index d770f3a612..4b4b31ad8c 100644 --- a/Marlin/pins_ULTIMAKER.h +++ b/Marlin/pins_ULTIMAKER.h @@ -34,49 +34,78 @@ #define LARGE_FLASH true -#define SERVO0_PIN 13 // untested +// +// Servos +// +#define SERVO0_PIN 13 // untested -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_MIN_PIN 22 -#define X_MAX_PIN 24 -#define X_ENABLE_PIN 27 +// +// Limit Switches +// +#define X_MIN_PIN 22 +#define X_MAX_PIN 24 +#define Y_MIN_PIN 26 +#define Y_MAX_PIN 28 +#define Z_MIN_PIN 30 +#define Z_MAX_PIN 32 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 33 -#define Y_MIN_PIN 26 -#define Y_MAX_PIN 28 -#define Y_ENABLE_PIN 29 +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 32 +#endif -#define Z_STEP_PIN 37 -#define Z_DIR_PIN 39 -#define Z_MIN_PIN 30 -#define Z_MAX_PIN 32 -#define Z_ENABLE_PIN 35 +// +// Steppers +// +#define X_STEP_PIN 25 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 27 -#define HEATER_BED_PIN 4 -#define TEMP_BED_PIN 10 +#define Y_STEP_PIN 31 +#define Y_DIR_PIN 33 +#define Y_ENABLE_PIN 29 -#define HEATER_0_PIN 2 -#define TEMP_0_PIN 8 +#define Z_STEP_PIN 37 +#define Z_DIR_PIN 39 +#define Z_ENABLE_PIN 35 -#define HEATER_1_PIN 3 -#define TEMP_1_PIN 9 +#define E0_STEP_PIN 43 +#define E0_DIR_PIN 45 +#define E0_ENABLE_PIN 41 -#define E0_STEP_PIN 43 -#define E0_DIR_PIN 45 -#define E0_ENABLE_PIN 41 +#define E1_STEP_PIN 49 +#define E1_DIR_PIN 47 +#define E1_ENABLE_PIN 48 -#define E1_STEP_PIN 49 -#define E1_DIR_PIN 47 -#define E1_ENABLE_PIN 48 +// +// Temperature Sensors +// +#define TEMP_0_PIN 8 // Analog Input +#define TEMP_1_PIN 9 // Analog Input +#define TEMP_BED_PIN 10 // Analog Input +// +// Heaters / Fans +// +#define HEATER_0_PIN 2 +#define HEATER_1_PIN 3 +#define HEATER_BED_PIN 4 + +#define FAN_PIN 7 + +// +// Misc. Functions +// #define SDSS 53 #define LED_PIN 13 -#define FAN_PIN 7 #define PS_ON_PIN 12 -#define SUICIDE_PIN 54 //PIN that has to be turned on right after start, to keep power flowing. +#define SUICIDE_PIN 54 // PIN that has to be turned on right after start, to keep power flowing. +// +// LCD / Controller +// #if ENABLED(ULTRA_LCD) #define BEEPER_PIN 18 @@ -90,16 +119,16 @@ #define LCD_PINS_D6 5 #define LCD_PINS_D7 6 - //buttons are directly attached + // buttons are directly attached #define BTN_EN1 40 #define BTN_EN2 42 #define BTN_ENC 19 #define SD_DETECT_PIN 38 - #else //!NEWPANEL - Old style panel with shift register + #else // !NEWPANEL - Old style panel with shift register - //buttons are attached to a shift register + // buttons are attached to a shift register #define SHIFT_CLK 38 #define SHIFT_LD 42 #define SHIFT_OUT 40 diff --git a/Marlin/pins_ULTIMAKER_OLD.h b/Marlin/pins_ULTIMAKER_OLD.h index 33bc26c9aa..b42ba69585 100644 --- a/Marlin/pins_ULTIMAKER_OLD.h +++ b/Marlin/pins_ULTIMAKER_OLD.h @@ -34,41 +34,64 @@ #define LARGE_FLASH true -#define X_STEP_PIN 25 -#define X_DIR_PIN 23 -#define X_MIN_PIN 15 -#define X_MAX_PIN 14 -#define X_ENABLE_PIN 27 +// +// Limit Switches +// +#define X_MIN_PIN 15 +#define X_MAX_PIN 14 +#define Y_MIN_PIN 17 +#define Y_MAX_PIN 16 +#define Z_MIN_PIN 19 +#define Z_MAX_PIN 18 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 33 -#define Y_MIN_PIN 17 -#define Y_MAX_PIN 16 -#define Y_ENABLE_PIN 29 +// +// Z Probe (when not Z_MIN_PIN) +// +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN 18 +#endif -#define Z_STEP_PIN 37 -#define Z_DIR_PIN 39 -#define Z_MIN_PIN 19 -#define Z_MAX_PIN 18 -#define Z_ENABLE_PIN 35 +// +// Steppers +// +#define X_STEP_PIN 25 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 27 -#define TEMP_0_PIN 8 -#define TEMP_1_PIN 1 +#define Y_STEP_PIN 31 +#define Y_DIR_PIN 33 +#define Y_ENABLE_PIN 29 -#define HEATER_0_PIN 2 -#define HEATER_1_PIN 1 +#define Z_STEP_PIN 37 +#define Z_DIR_PIN 39 +#define Z_ENABLE_PIN 35 -#define E0_STEP_PIN 43 -#define E0_DIR_PIN 45 -#define E0_ENABLE_PIN 41 +#define E0_STEP_PIN 43 +#define E0_DIR_PIN 45 +#define E0_ENABLE_PIN 41 -#define E1_STEP_PIN -1 -#define E1_DIR_PIN -1 -#define E1_ENABLE_PIN -1 +#define E1_STEP_PIN -1 +#define E1_DIR_PIN -1 +#define E1_ENABLE_PIN -1 -#define LCD_PINS_RS 24 -#define LCD_PINS_ENABLE 22 -#define LCD_PINS_D4 36 -#define LCD_PINS_D5 34 -#define LCD_PINS_D6 32 -#define LCD_PINS_D7 30 +// +// Temperature Sensors +// +#define TEMP_0_PIN 8 // Analog Input +#define TEMP_1_PIN 1 // Analog Input + +// +// Heaters / Fans +// +#define HEATER_0_PIN 2 +#define HEATER_1_PIN 1 + +// +// LCD / Controller +// +#define LCD_PINS_RS 24 +#define LCD_PINS_ENABLE 22 +#define LCD_PINS_D4 36 +#define LCD_PINS_D5 34 +#define LCD_PINS_D6 32 +#define LCD_PINS_D7 30 diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index 4e4d4a1893..73bdb0cf04 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -78,30 +78,41 @@ Planner planner; * A ring buffer of moves described in steps */ block_t Planner::block_buffer[BLOCK_BUFFER_SIZE]; -volatile uint8_t Planner::block_buffer_head = 0; // Index of the next block to be pushed -volatile uint8_t Planner::block_buffer_tail = 0; +volatile uint8_t Planner::block_buffer_head = 0, // Index of the next block to be pushed + Planner::block_buffer_tail = 0; -float Planner::max_feedrate_mm_s[NUM_AXIS], // Max speeds in mm per second - Planner::axis_steps_per_mm[NUM_AXIS], - Planner::steps_to_mm[NUM_AXIS]; +float Planner::max_feedrate_mm_s[XYZE_N], // Max speeds in mm per second + Planner::axis_steps_per_mm[XYZE_N], + Planner::steps_to_mm[XYZE_N]; -unsigned long Planner::max_acceleration_steps_per_s2[NUM_AXIS], - Planner::max_acceleration_mm_per_s2[NUM_AXIS]; // Use M201 to override by software +#if ENABLED(DISTINCT_E_FACTORS) + uint8_t Planner::last_extruder = 0; // Respond to extruder change +#endif + +uint32_t Planner::max_acceleration_steps_per_s2[XYZE_N], + Planner::max_acceleration_mm_per_s2[XYZE_N]; // Use M201 to override by software millis_t Planner::min_segment_time; float Planner::min_feedrate_mm_s, Planner::acceleration, // Normal acceleration mm/s^2 DEFAULT ACCELERATION for all printing moves. M204 SXXXX Planner::retract_acceleration, // Retract acceleration mm/s^2 filament pull-back and push-forward while standing still in the other axes M204 TXXXX Planner::travel_acceleration, // Travel acceleration mm/s^2 DEFAULT ACCELERATION for all NON printing moves. M204 MXXXX - Planner::max_xy_jerk, // The largest speed change requiring no acceleration - Planner::max_z_jerk, - Planner::max_e_jerk, + Planner::max_jerk[XYZE], // The largest speed change requiring no acceleration Planner::min_travel_feedrate_mm_s; -#if ENABLED(AUTO_BED_LEVELING_FEATURE) +#if HAS_ABL + bool Planner::abl_enabled = false; // Flag that auto bed leveling is enabled +#endif + +#if ABL_PLANAR matrix_3x3 Planner::bed_level_matrix; // Transform to compensate for bed level #endif +#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + float Planner::z_fade_height = 0.0, + Planner::inverse_z_fade_height = 0.0; +#endif + #if ENABLED(AUTOTEMP) float Planner::autotemp_max = 250, Planner::autotemp_min = 210, @@ -113,6 +124,8 @@ float Planner::min_feedrate_mm_s, long Planner::position[NUM_AXIS] = { 0 }; +uint32_t Planner::cutoff_long; + float Planner::previous_speed[NUM_AXIS], Planner::previous_nominal_speed; @@ -127,6 +140,15 @@ float Planner::previous_speed[NUM_AXIS], long Planner::axis_segment_time[2][3] = { {MAX_FREQ_TIME + 1, 0, 0}, {MAX_FREQ_TIME + 1, 0, 0} }; #endif +#if ENABLED(LIN_ADVANCE) + float Planner::extruder_advance_k = LIN_ADVANCE_K; + float Planner::position_float[NUM_AXIS] = { 0 }; +#endif + +#if ENABLED(ENSURE_SMOOTH_MOVES) + uint32_t Planner::block_buffer_runtime_us = 0; +#endif + /** * Class and Instance Methods */ @@ -135,59 +157,58 @@ Planner::Planner() { init(); } void Planner::init() { block_buffer_head = block_buffer_tail = 0; - memset(position, 0, sizeof(position)); // clear position - LOOP_XYZE(i) previous_speed[i] = 0.0; + ZERO(position); + #if ENABLED(LIN_ADVANCE) + ZERO(position_float); + #endif + ZERO(previous_speed); previous_nominal_speed = 0.0; - #if ENABLED(AUTO_BED_LEVELING_FEATURE) + #if ABL_PLANAR bed_level_matrix.set_to_identity(); #endif } +#define MINIMAL_STEP_RATE 120 + /** * Calculate trapezoid parameters, multiplying the entry- and exit-speeds * by the provided factors. */ -void Planner::calculate_trapezoid_for_block(block_t* block, float entry_factor, float exit_factor) { - unsigned long initial_rate = ceil(block->nominal_rate * entry_factor), - final_rate = ceil(block->nominal_rate * exit_factor); // (steps per second) +void Planner::calculate_trapezoid_for_block(block_t* const block, const float &entry_factor, const float &exit_factor) { + uint32_t initial_rate = ceil(block->nominal_rate * entry_factor), + final_rate = ceil(block->nominal_rate * exit_factor); // (steps per second) // Limit minimal step rate (Otherwise the timer will overflow.) - NOLESS(initial_rate, 120); - NOLESS(final_rate, 120); + NOLESS(initial_rate, MINIMAL_STEP_RATE); + NOLESS(final_rate, MINIMAL_STEP_RATE); - long accel = block->acceleration_steps_per_s2; - int32_t accelerate_steps = ceil(estimate_acceleration_distance(initial_rate, block->nominal_rate, accel)); - int32_t decelerate_steps = floor(estimate_acceleration_distance(block->nominal_rate, final_rate, -accel)); - - // Calculate the size of Plateau of Nominal Rate. - int32_t plateau_steps = block->step_event_count - accelerate_steps - decelerate_steps; + int32_t accel = block->acceleration_steps_per_s2, + accelerate_steps = ceil(estimate_acceleration_distance(initial_rate, block->nominal_rate, accel)), + decelerate_steps = floor(estimate_acceleration_distance(block->nominal_rate, final_rate, -accel)), + plateau_steps = block->step_event_count - accelerate_steps - decelerate_steps; // Is the Plateau of Nominal Rate smaller than nothing? That means no cruising, and we will // have to use intersection_distance() to calculate when to abort accel and start braking // in order to reach the final_rate exactly at the end of this block. if (plateau_steps < 0) { accelerate_steps = ceil(intersection_distance(initial_rate, final_rate, accel, block->step_event_count)); - accelerate_steps = max(accelerate_steps, 0); // Check limits due to numerical round-off + NOLESS(accelerate_steps, 0); // Check limits due to numerical round-off accelerate_steps = min((uint32_t)accelerate_steps, block->step_event_count);//(We can cast here to unsigned, because the above line ensures that we are above zero) plateau_steps = 0; } - #if ENABLED(ADVANCE) - volatile long initial_advance = block->advance * sq(entry_factor); - volatile long final_advance = block->advance * sq(exit_factor); - #endif // ADVANCE - // block->accelerate_until = accelerate_steps; // block->decelerate_after = accelerate_steps+plateau_steps; + CRITICAL_SECTION_START; // Fill variables used by the stepper in a critical section - if (!block->busy) { // Don't update variables if block is busy. + if (!TEST(block->flag, BLOCK_BIT_BUSY)) { // Don't update variables if block is busy. block->accelerate_until = accelerate_steps; block->decelerate_after = accelerate_steps + plateau_steps; block->initial_rate = initial_rate; block->final_rate = final_rate; #if ENABLED(ADVANCE) - block->initial_advance = initial_advance; - block->final_advance = final_advance; + block->initial_advance = block->advance * sq(entry_factor); + block->final_advance = block->advance * sq(exit_factor); #endif } CRITICAL_SECTION_END; @@ -203,30 +224,20 @@ void Planner::calculate_trapezoid_for_block(block_t* block, float entry_factor, // The kernel called by recalculate() when scanning the plan from last to first entry. -void Planner::reverse_pass_kernel(block_t* previous, block_t* current, block_t* next) { - if (!current) return; - UNUSED(previous); - - if (next) { - // If entry speed is already at the maximum entry speed, no need to recheck. Block is cruising. - // If not, block in state of acceleration or deceleration. Reset entry speed to maximum and - // check for maximum allowable speed reductions to ensure maximum possible planned speed. - float max_entry_speed = current->max_entry_speed; - if (current->entry_speed != max_entry_speed) { - - // If nominal length true, max junction speed is guaranteed to be reached. Only compute - // for max allowable speed if block is decelerating and nominal length is false. - if (!current->nominal_length_flag && max_entry_speed > next->entry_speed) { - current->entry_speed = min(max_entry_speed, - max_allowable_speed(-current->acceleration, next->entry_speed, current->millimeters)); - } - else { - current->entry_speed = max_entry_speed; - } - current->recalculate_flag = true; - - } - } // Skip last block. Already initialized and set for recalculation. +void Planner::reverse_pass_kernel(block_t* const current, const block_t *next) { + if (!current || !next) return; + // If entry speed is already at the maximum entry speed, no need to recheck. Block is cruising. + // If not, block in state of acceleration or deceleration. Reset entry speed to maximum and + // check for maximum allowable speed reductions to ensure maximum possible planned speed. + float max_entry_speed = current->max_entry_speed; + if (current->entry_speed != max_entry_speed) { + // If nominal length true, max junction speed is guaranteed to be reached. Only compute + // for max allowable speed if block is decelerating and nominal length is false. + current->entry_speed = (TEST(current->flag, BLOCK_BIT_NOMINAL_LENGTH) || max_entry_speed <= next->entry_speed) + ? max_entry_speed + : min(max_entry_speed, max_allowable_speed(-current->acceleration, next->entry_speed, current->millimeters)); + SBI(current->flag, BLOCK_BIT_RECALCULATE); + } } /** @@ -240,38 +251,39 @@ void Planner::reverse_pass() { block_t* block[3] = { NULL, NULL, NULL }; // Make a local copy of block_buffer_tail, because the interrupt can alter it - CRITICAL_SECTION_START; - uint8_t tail = block_buffer_tail; - CRITICAL_SECTION_END + // Is a critical section REALLY needed for a single byte change? + //CRITICAL_SECTION_START; + uint8_t tail = block_buffer_tail; + //CRITICAL_SECTION_END uint8_t b = BLOCK_MOD(block_buffer_head - 3); while (b != tail) { + if (block[0] && TEST(block[0]->flag, BLOCK_BIT_START_FROM_FULL_HALT)) break; b = prev_block_index(b); block[2] = block[1]; block[1] = block[0]; block[0] = &block_buffer[b]; - reverse_pass_kernel(block[0], block[1], block[2]); + reverse_pass_kernel(block[1], block[2]); } } } // The kernel called by recalculate() when scanning the plan from first to last entry. -void Planner::forward_pass_kernel(block_t* previous, block_t* current, block_t* next) { +void Planner::forward_pass_kernel(const block_t* previous, block_t* const current) { if (!previous) return; - UNUSED(next); // If the previous block is an acceleration block, but it is not long enough to complete the // full speed change within the block, we need to adjust the entry speed accordingly. Entry // speeds have already been reset, maximized, and reverse planned by reverse planner. // If nominal length is true, max junction speed is guaranteed to be reached. No need to recheck. - if (!previous->nominal_length_flag) { + if (!TEST(previous->flag, BLOCK_BIT_NOMINAL_LENGTH)) { if (previous->entry_speed < current->entry_speed) { - double entry_speed = min(current->entry_speed, + float entry_speed = min(current->entry_speed, max_allowable_speed(-previous->acceleration, previous->entry_speed, previous->millimeters)); // Check for junction speed change if (current->entry_speed != entry_speed) { current->entry_speed = entry_speed; - current->recalculate_flag = true; + SBI(current->flag, BLOCK_BIT_RECALCULATE); } } } @@ -288,9 +300,9 @@ void Planner::forward_pass() { block[0] = block[1]; block[1] = block[2]; block[2] = &block_buffer[b]; - forward_pass_kernel(block[0], block[1], block[2]); + forward_pass_kernel(block[0], block[1]); } - forward_pass_kernel(block[1], block[2], NULL); + forward_pass_kernel(block[1], block[2]); } /** @@ -300,19 +312,18 @@ void Planner::forward_pass() { */ void Planner::recalculate_trapezoids() { int8_t block_index = block_buffer_tail; - block_t* current; - block_t* next = NULL; + block_t *current, *next = NULL; while (block_index != block_buffer_head) { current = next; next = &block_buffer[block_index]; if (current) { // Recalculate if current block entry or exit junction speed has changed. - if (current->recalculate_flag || next->recalculate_flag) { + if (TEST(current->flag, BLOCK_BIT_RECALCULATE) || TEST(next->flag, BLOCK_BIT_RECALCULATE)) { // NOTE: Entry and exit factors always > 0 by all previous logic operations. float nom = current->nominal_speed; calculate_trapezoid_for_block(current, current->entry_speed / nom, next->entry_speed / nom); - current->recalculate_flag = false; // Reset current only to ensure next trapezoid is computed + CBI(current->flag, BLOCK_BIT_RECALCULATE); // Reset current only to ensure next trapezoid is computed } } block_index = next_block_index(block_index); @@ -321,7 +332,7 @@ void Planner::recalculate_trapezoids() { if (next) { float nom = next->nominal_speed; calculate_trapezoid_for_block(next, next->entry_speed / nom, (MINIMUM_PLANNER_SPEED) / nom); - next->recalculate_flag = false; + CBI(next->flag, BLOCK_BIT_RECALCULATE); } } @@ -523,57 +534,178 @@ void Planner::check_axes_activity() { #endif } +#if PLANNER_LEVELING + /** + * lx, ly, lz - logical (cartesian, not delta) positions in mm + */ + void Planner::apply_leveling(float &lx, float &ly, float &lz) { + + #if HAS_ABL + if (!abl_enabled) return; + #endif + + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + static float z_fade_factor = 1.0, last_raw_lz = -999.0; + if (z_fade_height) { + const float raw_lz = RAW_Z_POSITION(lz); + if (raw_lz >= z_fade_height) return; + if (last_raw_lz != raw_lz) { + last_raw_lz = raw_lz; + z_fade_factor = 1.0 - raw_lz * inverse_z_fade_height; + } + } + else + z_fade_factor = 1.0; + #else + constexpr float z_fade_factor = 1.0; + #endif + + #if ENABLED(MESH_BED_LEVELING) + + if (mbl.active()) + lz += mbl.get_z(RAW_X_POSITION(lx), RAW_Y_POSITION(ly), z_fade_factor); + + #elif ABL_PLANAR + + float dx = RAW_X_POSITION(lx) - (X_TILT_FULCRUM), + dy = RAW_Y_POSITION(ly) - (Y_TILT_FULCRUM), + dz = RAW_Z_POSITION(lz); + + apply_rotation_xyz(bed_level_matrix, dx, dy, dz); + + lx = LOGICAL_X_POSITION(dx + X_TILT_FULCRUM); + ly = LOGICAL_Y_POSITION(dy + Y_TILT_FULCRUM); + lz = LOGICAL_Z_POSITION(dz); + + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + + float tmp[XYZ] = { lx, ly, 0 }; + lz += bilinear_z_offset(tmp) * z_fade_factor; + + #endif + } + + void Planner::unapply_leveling(float logical[XYZ]) { + + #if HAS_ABL + if (!abl_enabled) return; + #endif + + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + if (z_fade_height && RAW_Z_POSITION(logical[Z_AXIS]) >= z_fade_height) return; + #endif + + #if ENABLED(MESH_BED_LEVELING) + + if (mbl.active()) { + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + const float c = mbl.get_z(RAW_X_POSITION(logical[X_AXIS]), RAW_Y_POSITION(logical[Y_AXIS]), 1.0); + logical[Z_AXIS] = (z_fade_height * (RAW_Z_POSITION(logical[Z_AXIS]) - c)) / (z_fade_height - c); + #else + logical[Z_AXIS] -= mbl.get_z(RAW_X_POSITION(logical[X_AXIS]), RAW_Y_POSITION(logical[Y_AXIS])); + #endif + } + + #elif ABL_PLANAR + + matrix_3x3 inverse = matrix_3x3::transpose(bed_level_matrix); + + float dx = RAW_X_POSITION(logical[X_AXIS]) - (X_TILT_FULCRUM), + dy = RAW_Y_POSITION(logical[Y_AXIS]) - (Y_TILT_FULCRUM), + dz = RAW_Z_POSITION(logical[Z_AXIS]); + + apply_rotation_xyz(inverse, dx, dy, dz); + + logical[X_AXIS] = LOGICAL_X_POSITION(dx + X_TILT_FULCRUM); + logical[Y_AXIS] = LOGICAL_Y_POSITION(dy + Y_TILT_FULCRUM); + logical[Z_AXIS] = LOGICAL_Z_POSITION(dz); + + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + const float c = bilinear_z_offset(logical); + logical[Z_AXIS] = (z_fade_height * (RAW_Z_POSITION(logical[Z_AXIS]) - c)) / (z_fade_height - c); + #else + logical[Z_AXIS] -= bilinear_z_offset(logical); + #endif + + #endif + } + +#endif // PLANNER_LEVELING + /** - * Planner::buffer_line + * Planner::_buffer_line * * Add a new linear movement to the buffer. * - * x,y,z,e - target position in mm - * fr_mm_s - (target) speed of the move - * extruder - target extruder + * Leveling and kinematics should be applied ahead of calling this. + * + * a,b,c,e - target positions in mm or degrees + * fr_mm_s - (target) speed of the move + * extruder - target extruder */ - -#if ENABLED(AUTO_BED_LEVELING_FEATURE) || ENABLED(MESH_BED_LEVELING) - void Planner::buffer_line(float x, float y, float z, const float& e, float fr_mm_s, const uint8_t extruder) -#else - void Planner::buffer_line(const float& x, const float& y, const float& z, const float& e, float fr_mm_s, const uint8_t extruder) -#endif // AUTO_BED_LEVELING_FEATURE -{ - // Calculate the buffer head after we push this byte - int next_buffer_head = next_block_index(block_buffer_head); - - // If the buffer is full: good! That means we are well ahead of the robot. - // Rest here until there is room in the buffer. - while (block_buffer_tail == next_buffer_head) idle(); - - #if ENABLED(MESH_BED_LEVELING) - if (mbl.active()) - z += mbl.get_z(x - home_offset[X_AXIS], y - home_offset[Y_AXIS]); - #elif ENABLED(AUTO_BED_LEVELING_FEATURE) - apply_rotation_xyz(bed_level_matrix, x, y, z); - #endif +void Planner::_buffer_line(const float &a, const float &b, const float &c, const float &e, float fr_mm_s, const uint8_t extruder) { // The target position of the tool in absolute steps // Calculate target position in absolute steps //this should be done after the wait, because otherwise a M92 code within the gcode disrupts this calculation somehow - long target[NUM_AXIS] = { - lround(x * axis_steps_per_mm[X_AXIS]), - lround(y * axis_steps_per_mm[Y_AXIS]), - lround(z * axis_steps_per_mm[Z_AXIS]), - lround(e * axis_steps_per_mm[E_AXIS]) + long target[XYZE] = { + lround(a * axis_steps_per_mm[X_AXIS]), + lround(b * axis_steps_per_mm[Y_AXIS]), + lround(c * axis_steps_per_mm[Z_AXIS]), + lround(e * axis_steps_per_mm[E_AXIS_N]) }; - long dx = target[X_AXIS] - position[X_AXIS], - dy = target[Y_AXIS] - position[Y_AXIS], - dz = target[Z_AXIS] - position[Z_AXIS]; + // When changing extruders recalculate steps corresponding to the E position + #if ENABLED(DISTINCT_E_FACTORS) + if (last_extruder != extruder && axis_steps_per_mm[E_AXIS_N] != axis_steps_per_mm[E_AXIS + last_extruder]) { + position[E_AXIS] = lround(position[E_AXIS] * axis_steps_per_mm[E_AXIS_N] * steps_to_mm[E_AXIS + last_extruder]); + last_extruder = extruder; + } + #endif + + #if ENABLED(LIN_ADVANCE) + float target_float[XYZE] = {a, b, c, e}; + float de_float = target_float[E_AXIS] - position_float[E_AXIS]; + float mm_D_float = sqrt(sq(target_float[X_AXIS] - position_float[X_AXIS]) + sq(target_float[Y_AXIS] - position_float[Y_AXIS])); + + memcpy(position_float, target_float, sizeof(position_float)); + #endif + + long da = target[X_AXIS] - position[X_AXIS], + db = target[Y_AXIS] - position[Y_AXIS], + dc = target[Z_AXIS] - position[Z_AXIS]; + + /* + SERIAL_ECHOPAIR(" Planner FR:", fr_mm_s); + SERIAL_CHAR(' '); + #if IS_KINEMATIC + SERIAL_ECHOPAIR("A:", a); + SERIAL_ECHOPAIR(" (", da); + SERIAL_ECHOPAIR(") B:", b); + #else + SERIAL_ECHOPAIR("X:", a); + SERIAL_ECHOPAIR(" (", da); + SERIAL_ECHOPAIR(") Y:", b); + #endif + SERIAL_ECHOPAIR(" (", db); + #if ENABLED(DELTA) + SERIAL_ECHOPAIR(") C:", c); + #else + SERIAL_ECHOPAIR(") Z:", c); + #endif + SERIAL_ECHOPAIR(" (", dc); + SERIAL_CHAR(')'); + SERIAL_EOL; + //*/ // DRYRUN ignores all temperature constraints and assures that the extruder is instantly satisfied - if (DEBUGGING(DRYRUN)) - position[E_AXIS] = target[E_AXIS]; + if (DEBUGGING(DRYRUN)) position[E_AXIS] = target[E_AXIS]; long de = target[E_AXIS] - position[E_AXIS]; - #if ENABLED(PREVENT_DANGEROUS_EXTRUDE) + #if ENABLED(PREVENT_COLD_EXTRUSION) if (de) { if (thermalManager.tooColdToExtrude(extruder)) { position[E_AXIS] = target[E_AXIS]; // Behave as if the move really took place, but ignore E part @@ -582,7 +714,7 @@ void Planner::check_axes_activity() { SERIAL_ECHOLNPGM(MSG_ERR_COLD_EXTRUDE_STOP); } #if ENABLED(PREVENT_LENGTHY_EXTRUDE) - if (labs(de) > axis_steps_per_mm[E_AXIS] * (EXTRUDE_MAXLENGTH)) { + if (labs(de) > (int32_t)axis_steps_per_mm[E_AXIS_N] * (EXTRUDE_MAXLENGTH)) { // It's not important to get max. extrusion length in a precision < 1mm, so save some cycles and cast to int position[E_AXIS] = target[E_AXIS]; // Behave as if the move really took place, but ignore E part de = 0; // no difference SERIAL_ECHO_START; @@ -592,49 +724,83 @@ void Planner::check_axes_activity() { } #endif + // Compute direction bit-mask for this block + uint8_t dm = 0; + #if CORE_IS_XY + if (da < 0) SBI(dm, X_HEAD); // Save the real Extruder (head) direction in X Axis + if (db < 0) SBI(dm, Y_HEAD); // ...and Y + if (dc < 0) SBI(dm, Z_AXIS); + if (da + db < 0) SBI(dm, A_AXIS); // Motor A direction + if (CORESIGN(da - db) < 0) SBI(dm, B_AXIS); // Motor B direction + #elif CORE_IS_XZ + if (da < 0) SBI(dm, X_HEAD); // Save the real Extruder (head) direction in X Axis + if (db < 0) SBI(dm, Y_AXIS); + if (dc < 0) SBI(dm, Z_HEAD); // ...and Z + if (da + dc < 0) SBI(dm, A_AXIS); // Motor A direction + if (CORESIGN(da - dc) < 0) SBI(dm, C_AXIS); // Motor C direction + #elif CORE_IS_YZ + if (da < 0) SBI(dm, X_AXIS); + if (db < 0) SBI(dm, Y_HEAD); // Save the real Extruder (head) direction in Y Axis + if (dc < 0) SBI(dm, Z_HEAD); // ...and Z + if (db + dc < 0) SBI(dm, B_AXIS); // Motor B direction + if (CORESIGN(db - dc) < 0) SBI(dm, C_AXIS); // Motor C direction + #else + if (da < 0) SBI(dm, X_AXIS); + if (db < 0) SBI(dm, Y_AXIS); + if (dc < 0) SBI(dm, Z_AXIS); + #endif + if (de < 0) SBI(dm, E_AXIS); + + float esteps_float = de * volumetric_multiplier[extruder] * flow_percentage[extruder] * 0.01; + int32_t esteps = abs(esteps_float) + 0.5; + + // Calculate the buffer head after we push this byte + int8_t next_buffer_head = next_block_index(block_buffer_head); + + // If the buffer is full: good! That means we are well ahead of the robot. + // Rest here until there is room in the buffer. + while (block_buffer_tail == next_buffer_head) idle(); + // Prepare to set up new block block_t* block = &block_buffer[block_buffer_head]; - // Mark block as not busy (Not executed by the stepper interrupt) - block->busy = false; + // Clear all flags, including the "busy" bit + block->flag = 0; + + // Set direction bits + block->direction_bits = dm; // Number of steps for each axis - #if ENABLED(COREXY) - // corexy planning - // these equations follow the form of the dA and dB equations on http://www.corexy.com/theory.html - block->steps[A_AXIS] = labs(dx + dy); - block->steps[B_AXIS] = labs(dx - dy); - block->steps[Z_AXIS] = labs(dz); - #elif ENABLED(COREXZ) - // corexz planning - block->steps[A_AXIS] = labs(dx + dz); - block->steps[Y_AXIS] = labs(dy); - block->steps[C_AXIS] = labs(dx - dz); - #elif ENABLED(COREYZ) - // coreyz planning - block->steps[X_AXIS] = labs(dx); - block->steps[B_AXIS] = labs(dy + dz); - block->steps[C_AXIS] = labs(dy - dz); + // See http://www.corexy.com/theory.html + #if CORE_IS_XY + block->steps[A_AXIS] = labs(da + db); + block->steps[B_AXIS] = labs(da - db); + block->steps[Z_AXIS] = labs(dc); + #elif CORE_IS_XZ + block->steps[A_AXIS] = labs(da + dc); + block->steps[Y_AXIS] = labs(db); + block->steps[C_AXIS] = labs(da - dc); + #elif CORE_IS_YZ + block->steps[X_AXIS] = labs(da); + block->steps[B_AXIS] = labs(db + dc); + block->steps[C_AXIS] = labs(db - dc); #else // default non-h-bot planning - block->steps[X_AXIS] = labs(dx); - block->steps[Y_AXIS] = labs(dy); - block->steps[Z_AXIS] = labs(dz); + block->steps[X_AXIS] = labs(da); + block->steps[Y_AXIS] = labs(db); + block->steps[Z_AXIS] = labs(dc); #endif - block->steps[E_AXIS] = labs(de); - block->steps[E_AXIS] *= volumetric_multiplier[extruder]; - block->steps[E_AXIS] *= extruder_multiplier[extruder]; - block->steps[E_AXIS] /= 100; - block->step_event_count = max(block->steps[X_AXIS], max(block->steps[Y_AXIS], max(block->steps[Z_AXIS], block->steps[E_AXIS]))); + block->steps[E_AXIS] = esteps; + block->step_event_count = MAX4(block->steps[X_AXIS], block->steps[Y_AXIS], block->steps[Z_AXIS], esteps); // Bail if this is a zero-length block - if (block->step_event_count <= dropsegments) return; + if (block->step_event_count < MIN_STEPS_PER_SEGMENT) return; // For a mixing extruder, get a magnified step_event_count for each #if ENABLED(MIXING_EXTRUDER) for (uint8_t i = 0; i < MIXING_STEPPERS; i++) - block->mix_event_count[i] = (mixing_factor[i] < 0.0001) ? 0 : block->step_event_count / mixing_factor[i]; + block->mix_event_count[i] = mixing_factor[i] * block->step_event_count; #endif #if FAN_COUNT > 0 @@ -646,38 +812,10 @@ void Planner::check_axes_activity() { block->e_to_p_pressure = baricuda_e_to_p_pressure; #endif - // Compute direction bits for this block - uint8_t db = 0; - #if ENABLED(COREXY) - if (dx < 0) SBI(db, X_HEAD); // Save the real Extruder (head) direction in X Axis - if (dy < 0) SBI(db, Y_HEAD); // ...and Y - if (dz < 0) SBI(db, Z_AXIS); - if (dx + dy < 0) SBI(db, A_AXIS); // Motor A direction - if (dx - dy < 0) SBI(db, B_AXIS); // Motor B direction - #elif ENABLED(COREXZ) - if (dx < 0) SBI(db, X_HEAD); // Save the real Extruder (head) direction in X Axis - if (dy < 0) SBI(db, Y_AXIS); - if (dz < 0) SBI(db, Z_HEAD); // ...and Z - if (dx + dz < 0) SBI(db, A_AXIS); // Motor A direction - if (dx - dz < 0) SBI(db, C_AXIS); // Motor C direction - #elif ENABLED(COREYZ) - if (dx < 0) SBI(db, X_AXIS); - if (dy < 0) SBI(db, Y_HEAD); // Save the real Extruder (head) direction in Y Axis - if (dz < 0) SBI(db, Z_HEAD); // ...and Z - if (dy + dz < 0) SBI(db, B_AXIS); // Motor B direction - if (dy - dz < 0) SBI(db, C_AXIS); // Motor C direction - #else - if (dx < 0) SBI(db, X_AXIS); - if (dy < 0) SBI(db, Y_AXIS); - if (dz < 0) SBI(db, Z_AXIS); - #endif - if (de < 0) SBI(db, E_AXIS); - block->direction_bits = db; - block->active_extruder = extruder; //enable active axes - #if ENABLED(COREXY) + #if CORE_IS_XY if (block->steps[A_AXIS] || block->steps[B_AXIS]) { enable_x(); enable_y(); @@ -685,12 +823,18 @@ void Planner::check_axes_activity() { #if DISABLED(Z_LATE_ENABLE) if (block->steps[Z_AXIS]) enable_z(); #endif - #elif ENABLED(COREXZ) + #elif CORE_IS_XZ if (block->steps[A_AXIS] || block->steps[C_AXIS]) { enable_x(); enable_z(); } if (block->steps[Y_AXIS]) enable_y(); + #elif CORE_IS_YZ + if (block->steps[B_AXIS] || block->steps[C_AXIS]) { + enable_y(); + enable_z(); + } + if (block->steps[X_AXIS]) enable_x(); #else if (block->steps[X_AXIS]) enable_x(); if (block->steps[Y_AXIS]) enable_y(); @@ -700,11 +844,11 @@ void Planner::check_axes_activity() { #endif // Enable extruder(s) - if (block->steps[E_AXIS]) { + if (esteps) { #if ENABLED(DISABLE_INACTIVE_EXTRUDER) // Enable only the selected extruder - for (int i = 0; i < EXTRUDERS; i++) + for (int8_t i = 0; i < EXTRUDERS; i++) if (g_uc_extruder_last_move[i] > 0) g_uc_extruder_last_move[i]--; switch(extruder) { @@ -769,7 +913,7 @@ void Planner::check_axes_activity() { #endif } - if (block->steps[E_AXIS]) + if (esteps) NOLESS(fr_mm_s, min_feedrate_mm_s); else NOLESS(fr_mm_s, min_travel_feedrate_mm_s); @@ -782,45 +926,45 @@ void Planner::check_axes_activity() { * So we need to create other 2 "AXIS", named X_HEAD and Y_HEAD, meaning the real displacement of the Head. * Having the real displacement of the head, we can calculate the total movement length and apply the desired speed. */ - #if ENABLED(COREXY) || ENABLED(COREXZ) || ENABLED(COREYZ) + #if IS_CORE float delta_mm[7]; - #if ENABLED(COREXY) - delta_mm[X_HEAD] = dx * steps_to_mm[A_AXIS]; - delta_mm[Y_HEAD] = dy * steps_to_mm[B_AXIS]; - delta_mm[Z_AXIS] = dz * steps_to_mm[Z_AXIS]; - delta_mm[A_AXIS] = (dx + dy) * steps_to_mm[A_AXIS]; - delta_mm[B_AXIS] = (dx - dy) * steps_to_mm[B_AXIS]; - #elif ENABLED(COREXZ) - delta_mm[X_HEAD] = dx * steps_to_mm[A_AXIS]; - delta_mm[Y_AXIS] = dy * steps_to_mm[Y_AXIS]; - delta_mm[Z_HEAD] = dz * steps_to_mm[C_AXIS]; - delta_mm[A_AXIS] = (dx + dz) * steps_to_mm[A_AXIS]; - delta_mm[C_AXIS] = (dx - dz) * steps_to_mm[C_AXIS]; - #elif ENABLED(COREYZ) - delta_mm[X_AXIS] = dx * steps_to_mm[X_AXIS]; - delta_mm[Y_HEAD] = dy * steps_to_mm[B_AXIS]; - delta_mm[Z_HEAD] = dz * steps_to_mm[C_AXIS]; - delta_mm[B_AXIS] = (dy + dz) * steps_to_mm[B_AXIS]; - delta_mm[C_AXIS] = (dy - dz) * steps_to_mm[C_AXIS]; + #if CORE_IS_XY + delta_mm[X_HEAD] = da * steps_to_mm[A_AXIS]; + delta_mm[Y_HEAD] = db * steps_to_mm[B_AXIS]; + delta_mm[Z_AXIS] = dc * steps_to_mm[Z_AXIS]; + delta_mm[A_AXIS] = (da + db) * steps_to_mm[A_AXIS]; + delta_mm[B_AXIS] = CORESIGN(da - db) * steps_to_mm[B_AXIS]; + #elif CORE_IS_XZ + delta_mm[X_HEAD] = da * steps_to_mm[A_AXIS]; + delta_mm[Y_AXIS] = db * steps_to_mm[Y_AXIS]; + delta_mm[Z_HEAD] = dc * steps_to_mm[C_AXIS]; + delta_mm[A_AXIS] = (da + dc) * steps_to_mm[A_AXIS]; + delta_mm[C_AXIS] = CORESIGN(da - dc) * steps_to_mm[C_AXIS]; + #elif CORE_IS_YZ + delta_mm[X_AXIS] = da * steps_to_mm[X_AXIS]; + delta_mm[Y_HEAD] = db * steps_to_mm[B_AXIS]; + delta_mm[Z_HEAD] = dc * steps_to_mm[C_AXIS]; + delta_mm[B_AXIS] = (db + dc) * steps_to_mm[B_AXIS]; + delta_mm[C_AXIS] = CORESIGN(db - dc) * steps_to_mm[C_AXIS]; #endif #else float delta_mm[4]; - delta_mm[X_AXIS] = dx * steps_to_mm[X_AXIS]; - delta_mm[Y_AXIS] = dy * steps_to_mm[Y_AXIS]; - delta_mm[Z_AXIS] = dz * steps_to_mm[Z_AXIS]; + delta_mm[X_AXIS] = da * steps_to_mm[X_AXIS]; + delta_mm[Y_AXIS] = db * steps_to_mm[Y_AXIS]; + delta_mm[Z_AXIS] = dc * steps_to_mm[Z_AXIS]; #endif - delta_mm[E_AXIS] = 0.01 * (de * steps_to_mm[E_AXIS]) * volumetric_multiplier[extruder] * extruder_multiplier[extruder]; + delta_mm[E_AXIS] = esteps_float * steps_to_mm[E_AXIS_N]; - if (block->steps[X_AXIS] <= dropsegments && block->steps[Y_AXIS] <= dropsegments && block->steps[Z_AXIS] <= dropsegments) { + if (block->steps[X_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[Y_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[Z_AXIS] < MIN_STEPS_PER_SEGMENT) { block->millimeters = fabs(delta_mm[E_AXIS]); } else { block->millimeters = sqrt( - #if ENABLED(COREXY) + #if CORE_IS_XY sq(delta_mm[X_HEAD]) + sq(delta_mm[Y_HEAD]) + sq(delta_mm[Z_AXIS]) - #elif ENABLED(COREXZ) + #elif CORE_IS_XZ sq(delta_mm[X_HEAD]) + sq(delta_mm[Y_AXIS]) + sq(delta_mm[Z_HEAD]) - #elif ENABLED(COREYZ) + #elif CORE_IS_YZ sq(delta_mm[X_AXIS]) + sq(delta_mm[Y_HEAD]) + sq(delta_mm[Z_HEAD]) #else sq(delta_mm[X_AXIS]) + sq(delta_mm[Y_AXIS]) + sq(delta_mm[Z_AXIS]) @@ -835,24 +979,31 @@ void Planner::check_axes_activity() { int moves_queued = movesplanned(); // Slow down when the buffer starts to empty, rather than wait at the corner for a buffer refill - #if ENABLED(OLD_SLOWDOWN) || ENABLED(SLOWDOWN) - bool mq = moves_queued > 1 && moves_queued < (BLOCK_BUFFER_SIZE) / 2; - #if ENABLED(OLD_SLOWDOWN) - if (mq) fr_mm_s *= 2.0 * moves_queued / (BLOCK_BUFFER_SIZE); - #endif - #if ENABLED(SLOWDOWN) - // segment time im micro seconds - unsigned long segment_time = lround(1000000.0/inverse_mm_s); - if (mq) { - if (segment_time < min_segment_time) { - // buffer is draining, add extra time. The amount of time added increases if the buffer is still emptied more. - inverse_mm_s = 1000000.0 / (segment_time + lround(2 * (min_segment_time - segment_time) / moves_queued)); - #ifdef XY_FREQUENCY_LIMIT - segment_time = lround(1000000.0 / inverse_mm_s); - #endif - } + #if ENABLED(SLOWDOWN) + // Segment time im micro seconds + unsigned long segment_time = lround(1000000.0 / inverse_mm_s); + if (moves_queued > 1 && moves_queued < (BLOCK_BUFFER_SIZE) / 2) { + if (segment_time < min_segment_time) { + // buffer is draining, add extra time. The amount of time added increases if the buffer is still emptied more. + inverse_mm_s = 1000000.0 / (segment_time + lround(2 * (min_segment_time - segment_time) / moves_queued)); + #if defined(XY_FREQUENCY_LIMIT) || ENABLED(ENSURE_SMOOTH_MOVES) + segment_time = lround(1000000.0 / inverse_mm_s); + #endif } + } + #endif + + #if ENABLED(ENSURE_SMOOTH_MOVES) + #if DISABLED(SLOWDOWN) + unsigned long segment_time = lround(1000000.0 / inverse_mm_s); #endif + if (segment_time < (MIN_BLOCK_TIME) * 1000UL) { + // buffer will be draining, set to MIN_BLOCK_TIME. + inverse_mm_s = 1000000.0 / (1000.0 * (MIN_BLOCK_TIME)); + segment_time = (MIN_BLOCK_TIME) * 1000UL; + } + block->segment_time = segment_time; + block_buffer_runtime_us += segment_time; #endif block->nominal_speed = block->millimeters * inverse_mm_s; // (mm/sec) Always > 0 @@ -862,7 +1013,7 @@ void Planner::check_axes_activity() { static float filwidth_e_count = 0, filwidth_delay_dist = 0; //FMM update ring buffer used for delay with filament measurements - if (extruder == FILAMENT_SENSOR_EXTRUDER_NUM && filwidth_delay_index2 >= 0) { //only for extruder with filament sensor and if ring buffer is initialized + if (extruder == FILAMENT_SENSOR_EXTRUDER_NUM && filwidth_delay_index[1] >= 0) { //only for extruder with filament sensor and if ring buffer is initialized const int MMD_CM = MAX_MEASUREMENT_DELAY + 1, MMD_MM = MMD_CM * 10; @@ -877,31 +1028,29 @@ void Planner::check_axes_activity() { while (filwidth_delay_dist >= MMD_MM) filwidth_delay_dist -= MMD_MM; // Convert into an index into the measurement array - filwidth_delay_index1 = (int)(filwidth_delay_dist * 0.1 + 0.0001); + filwidth_delay_index[0] = (int)(filwidth_delay_dist * 0.1 + 0.0001); // If the index has changed (must have gone forward)... - if (filwidth_delay_index1 != filwidth_delay_index2) { + if (filwidth_delay_index[0] != filwidth_delay_index[1]) { filwidth_e_count = 0; // Reset the E movement counter int8_t meas_sample = thermalManager.widthFil_to_size_ratio() - 100; // Subtract 100 to reduce magnitude - to store in a signed char do { - filwidth_delay_index2 = (filwidth_delay_index2 + 1) % MMD_CM; // The next unused slot - measurement_delay[filwidth_delay_index2] = meas_sample; // Store the measurement - } while (filwidth_delay_index1 != filwidth_delay_index2); // More slots to fill? + filwidth_delay_index[1] = (filwidth_delay_index[1] + 1) % MMD_CM; // The next unused slot + measurement_delay[filwidth_delay_index[1]] = meas_sample; // Store the measurement + } while (filwidth_delay_index[0] != filwidth_delay_index[1]); // More slots to fill? } } } #endif // Calculate and limit speed in mm/sec for each axis - float current_speed[NUM_AXIS]; - float speed_factor = 1.0; //factor <=1 do decrease speed + float current_speed[NUM_AXIS], speed_factor = 1.0; // factor <1 decreases speed LOOP_XYZE(i) { - current_speed[i] = delta_mm[i] * inverse_mm_s; - float cs = fabs(current_speed[i]), mf = max_feedrate_mm_s[i]; - if (cs > mf) speed_factor = min(speed_factor, mf / cs); + float cs = fabs(current_speed[i] = delta_mm[i] * inverse_mm_s); + if (cs > max_feedrate_mm_s[i]) NOMORE(speed_factor, max_feedrate_mm_s[i] / cs); } - // Max segement time in us. + // Max segment time in µs. #ifdef XY_FREQUENCY_LIMIT // Check and limit the xy direction change frequency @@ -930,12 +1079,12 @@ void Planner::check_axes_activity() { } ys0 = axis_segment_time[Y_AXIS][0] = ys0 + segment_time; - long max_x_segment_time = max(xs0, max(xs1, xs2)), - max_y_segment_time = max(ys0, max(ys1, ys2)), + long max_x_segment_time = MAX3(xs0, xs1, xs2), + max_y_segment_time = MAX3(ys0, ys1, ys2), min_xy_segment_time = min(max_x_segment_time, max_y_segment_time); if (min_xy_segment_time < MAX_FREQ_TIME) { float low_sf = speed_factor * min_xy_segment_time / (MAX_FREQ_TIME); - speed_factor = min(speed_factor, low_sf); + NOMORE(speed_factor, low_sf); } #endif // XY_FREQUENCY_LIMIT @@ -947,100 +1096,192 @@ void Planner::check_axes_activity() { } // Compute and limit the acceleration rate for the trapezoid generator. - float steps_per_mm = block->step_event_count / block->millimeters; + float steps_per_mm = block->step_event_count * inverse_millimeters; + uint32_t accel; if (!block->steps[X_AXIS] && !block->steps[Y_AXIS] && !block->steps[Z_AXIS]) { - block->acceleration_steps_per_s2 = ceil(retract_acceleration * steps_per_mm); // convert to: acceleration steps/sec^2 + // convert to: acceleration steps/sec^2 + accel = ceil(retract_acceleration * steps_per_mm); } else { + #define LIMIT_ACCEL_LONG(AXIS,INDX) do{ \ + if (block->steps[AXIS] && max_acceleration_steps_per_s2[AXIS+INDX] < accel) { \ + const uint32_t comp = max_acceleration_steps_per_s2[AXIS+INDX] * block->step_event_count; \ + if (accel * block->steps[AXIS] > comp) accel = comp / block->steps[AXIS]; \ + } \ + }while(0) + + #define LIMIT_ACCEL_FLOAT(AXIS,INDX) do{ \ + if (block->steps[AXIS] && max_acceleration_steps_per_s2[AXIS+INDX] < accel) { \ + const float comp = (float)max_acceleration_steps_per_s2[AXIS+INDX] * (float)block->step_event_count; \ + if ((float)accel * (float)block->steps[AXIS] > comp) accel = comp / (float)block->steps[AXIS]; \ + } \ + }while(0) + + // Start with print or travel acceleration + accel = ceil((esteps ? acceleration : travel_acceleration) * steps_per_mm); + // Limit acceleration per axis - block->acceleration_steps_per_s2 = ceil((block->steps[E_AXIS] ? acceleration : travel_acceleration) * steps_per_mm); - if (max_acceleration_steps_per_s2[X_AXIS] < (block->acceleration_steps_per_s2 * block->steps[X_AXIS]) / block->step_event_count) - block->acceleration_steps_per_s2 = (max_acceleration_steps_per_s2[X_AXIS] * block->step_event_count) / block->steps[X_AXIS]; - if (max_acceleration_steps_per_s2[Y_AXIS] < (block->acceleration_steps_per_s2 * block->steps[Y_AXIS]) / block->step_event_count) - block->acceleration_steps_per_s2 = (max_acceleration_steps_per_s2[Y_AXIS] * block->step_event_count) / block->steps[Y_AXIS]; - if (max_acceleration_steps_per_s2[Z_AXIS] < (block->acceleration_steps_per_s2 * block->steps[Z_AXIS]) / block->step_event_count) - block->acceleration_steps_per_s2 = (max_acceleration_steps_per_s2[Z_AXIS] * block->step_event_count) / block->steps[Z_AXIS]; - if (max_acceleration_steps_per_s2[E_AXIS] < (block->acceleration_steps_per_s2 * block->steps[E_AXIS]) / block->step_event_count) - block->acceleration_steps_per_s2 = (max_acceleration_steps_per_s2[E_AXIS] * block->step_event_count) / block->steps[E_AXIS]; + if (block->step_event_count <= cutoff_long) { + LIMIT_ACCEL_LONG(X_AXIS,0); + LIMIT_ACCEL_LONG(Y_AXIS,0); + LIMIT_ACCEL_LONG(Z_AXIS,0); + LIMIT_ACCEL_LONG(E_AXIS,extruder); + } + else { + LIMIT_ACCEL_FLOAT(X_AXIS,0); + LIMIT_ACCEL_FLOAT(Y_AXIS,0); + LIMIT_ACCEL_FLOAT(Z_AXIS,0); + LIMIT_ACCEL_FLOAT(E_AXIS,extruder); + } } - block->acceleration = block->acceleration_steps_per_s2 / steps_per_mm; - block->acceleration_rate = (long)(block->acceleration_steps_per_s2 * 16777216.0 / ((F_CPU) * 0.125)); + block->acceleration_steps_per_s2 = accel; + block->acceleration = accel / steps_per_mm; + block->acceleration_rate = (long)(accel * 16777216.0 / ((F_CPU) * 0.125)); // * 8.388608 + + // Initial limit on the segment entry velocity + float vmax_junction; #if 0 // Use old jerk for now float junction_deviation = 0.1; // Compute path unit vector - double unit_vec[3]; + double unit_vec[XYZ] = { + delta_mm[X_AXIS] * inverse_millimeters, + delta_mm[Y_AXIS] * inverse_millimeters, + delta_mm[Z_AXIS] * inverse_millimeters + }; - unit_vec[X_AXIS] = delta_mm[X_AXIS] * inverse_millimeters; - unit_vec[Y_AXIS] = delta_mm[Y_AXIS] * inverse_millimeters; - unit_vec[Z_AXIS] = delta_mm[Z_AXIS] * inverse_millimeters; + /* + Compute maximum allowable entry speed at junction by centripetal acceleration approximation. - // Compute maximum allowable entry speed at junction by centripetal acceleration approximation. - // Let a circle be tangent to both previous and current path line segments, where the junction - // deviation is defined as the distance from the junction to the closest edge of the circle, - // collinear with the circle center. The circular segment joining the two paths represents the - // path of centripetal acceleration. Solve for max velocity based on max acceleration about the - // radius of the circle, defined indirectly by junction deviation. This may be also viewed as - // path width or max_jerk in the previous grbl version. This approach does not actually deviate - // from path, but used as a robust way to compute cornering speeds, as it takes into account the - // nonlinearities of both the junction angle and junction velocity. - double vmax_junction = MINIMUM_PLANNER_SPEED; // Set default max junction speed + Let a circle be tangent to both previous and current path line segments, where the junction + deviation is defined as the distance from the junction to the closest edge of the circle, + collinear with the circle center. + + The circular segment joining the two paths represents the path of centripetal acceleration. + Solve for max velocity based on max acceleration about the radius of the circle, defined + indirectly by junction deviation. + + This may be also viewed as path width or max_jerk in the previous grbl version. This approach + does not actually deviate from path, but used as a robust way to compute cornering speeds, as + it takes into account the nonlinearities of both the junction angle and junction velocity. + */ + + vmax_junction = MINIMUM_PLANNER_SPEED; // Set default max junction speed // Skip first block or when previous_nominal_speed is used as a flag for homing and offset cycles. - if ((block_buffer_head != block_buffer_tail) && (previous_nominal_speed > 0.0)) { + if (block_buffer_head != block_buffer_tail && previous_nominal_speed > 0.0) { // Compute cosine of angle between previous and current path. (prev_unit_vec is negative) // NOTE: Max junction velocity is computed without sin() or acos() by trig half angle identity. - double cos_theta = - previous_unit_vec[X_AXIS] * unit_vec[X_AXIS] - - previous_unit_vec[Y_AXIS] * unit_vec[Y_AXIS] - - previous_unit_vec[Z_AXIS] * unit_vec[Z_AXIS] ; + float cos_theta = - previous_unit_vec[X_AXIS] * unit_vec[X_AXIS] + - previous_unit_vec[Y_AXIS] * unit_vec[Y_AXIS] + - previous_unit_vec[Z_AXIS] * unit_vec[Z_AXIS] ; // Skip and use default max junction speed for 0 degree acute junction. if (cos_theta < 0.95) { vmax_junction = min(previous_nominal_speed, block->nominal_speed); // Skip and avoid divide by zero for straight junctions at 180 degrees. Limit to min() of nominal speeds. if (cos_theta > -0.95) { // Compute maximum junction velocity based on maximum acceleration and junction deviation - double sin_theta_d2 = sqrt(0.5 * (1.0 - cos_theta)); // Trig half angle identity. Always positive. - vmax_junction = min(vmax_junction, - sqrt(block->acceleration * junction_deviation * sin_theta_d2 / (1.0 - sin_theta_d2))); + float sin_theta_d2 = sqrt(0.5 * (1.0 - cos_theta)); // Trig half angle identity. Always positive. + NOMORE(vmax_junction, sqrt(block->acceleration * junction_deviation * sin_theta_d2 / (1.0 - sin_theta_d2))); } } } #endif - // Start with a safe speed - float vmax_junction = max_xy_jerk * 0.5, - vmax_junction_factor = 1.0, - mz2 = max_z_jerk * 0.5, - me2 = max_e_jerk * 0.5, - csz = current_speed[Z_AXIS], - cse = current_speed[E_AXIS]; - if (fabs(csz) > mz2) vmax_junction = min(vmax_junction, mz2); - if (fabs(cse) > me2) vmax_junction = min(vmax_junction, me2); - vmax_junction = min(vmax_junction, block->nominal_speed); - float safe_speed = vmax_junction; + /** + * Adapted from Prusa MKS firmware + * + * Start with a safe speed (from which the machine may halt to stop immediately). + */ - if ((moves_queued > 1) && (previous_nominal_speed > 0.0001)) { - float dsx = current_speed[X_AXIS] - previous_speed[X_AXIS], - dsy = current_speed[Y_AXIS] - previous_speed[Y_AXIS], - dsz = fabs(csz - previous_speed[Z_AXIS]), - dse = fabs(cse - previous_speed[E_AXIS]), - jerk = HYPOT(dsx, dsy); + // Exit speed limited by a jerk to full halt of a previous last segment + static float previous_safe_speed; - // if ((fabs(previous_speed[X_AXIS]) > 0.0001) || (fabs(previous_speed[Y_AXIS]) > 0.0001)) { - vmax_junction = block->nominal_speed; - // } - if (jerk > max_xy_jerk) vmax_junction_factor = max_xy_jerk / jerk; - if (dsz > max_z_jerk) vmax_junction_factor = min(vmax_junction_factor, max_z_jerk / dsz); - if (dse > max_e_jerk) vmax_junction_factor = min(vmax_junction_factor, max_e_jerk / dse); - - vmax_junction = min(previous_nominal_speed, vmax_junction * vmax_junction_factor); // Limit speed to max previous speed + float safe_speed = block->nominal_speed; + bool limited = false; + LOOP_XYZE(i) { + float jerk = fabs(current_speed[i]); + if (jerk > max_jerk[i]) { + // The actual jerk is lower if it has been limited by the XY jerk. + if (limited) { + // Spare one division by a following gymnastics: + // Instead of jerk *= safe_speed / block->nominal_speed, + // multiply max_jerk[i] by the divisor. + jerk *= safe_speed; + float mjerk = max_jerk[i] * block->nominal_speed; + if (jerk > mjerk) safe_speed *= mjerk / jerk; + } + else { + safe_speed = max_jerk[i]; + limited = true; + } + } } + + if (moves_queued > 1 && previous_nominal_speed > 0.0001) { + // Estimate a maximum velocity allowed at a joint of two successive segments. + // If this maximum velocity allowed is lower than the minimum of the entry / exit safe velocities, + // then the machine is not coasting anymore and the safe entry / exit velocities shall be used. + + // The junction velocity will be shared between successive segments. Limit the junction velocity to their minimum. + bool prev_speed_larger = previous_nominal_speed > block->nominal_speed; + float smaller_speed_factor = prev_speed_larger ? (block->nominal_speed / previous_nominal_speed) : (previous_nominal_speed / block->nominal_speed); + // Pick the smaller of the nominal speeds. Higher speed shall not be achieved at the junction during coasting. + vmax_junction = prev_speed_larger ? block->nominal_speed : previous_nominal_speed; + // Factor to multiply the previous / current nominal velocities to get componentwise limited velocities. + float v_factor = 1.f; + limited = false; + // Now limit the jerk in all axes. + LOOP_XYZE(axis) { + // Limit an axis. We have to differentiate: coasting, reversal of an axis, full stop. + float v_exit = previous_speed[axis], v_entry = current_speed[axis]; + if (prev_speed_larger) v_exit *= smaller_speed_factor; + if (limited) { + v_exit *= v_factor; + v_entry *= v_factor; + } + // Calculate jerk depending on whether the axis is coasting in the same direction or reversing. + float jerk = + (v_exit > v_entry) ? + ((v_entry > 0.f || v_exit < 0.f) ? + // coasting + (v_exit - v_entry) : + // axis reversal + max(v_exit, -v_entry)) : + // v_exit <= v_entry + ((v_entry < 0.f || v_exit > 0.f) ? + // coasting + (v_entry - v_exit) : + // axis reversal + max(-v_exit, v_entry)); + if (jerk > max_jerk[axis]) { + v_factor *= max_jerk[axis] / jerk; + limited = true; + } + } + if (limited) vmax_junction *= v_factor; + // Now the transition velocity is known, which maximizes the shared exit / entry velocity while + // respecting the jerk factors, it may be possible, that applying separate safe exit / entry velocities will achieve faster prints. + float vmax_junction_threshold = vmax_junction * 0.99f; + if (previous_safe_speed > vmax_junction_threshold && safe_speed > vmax_junction_threshold) { + // Not coasting. The machine will stop and start the movements anyway, + // better to start the segment from start. + SBI(block->flag, BLOCK_BIT_START_FROM_FULL_HALT); + vmax_junction = safe_speed; + } + } + else { + SBI(block->flag, BLOCK_BIT_START_FROM_FULL_HALT); + vmax_junction = safe_speed; + } + + // Max entry speed of this block equals the max exit speed of the previous block. block->max_entry_speed = vmax_junction; // Initialize block entry speed. Compute based on deceleration to user-defined MINIMUM_PLANNER_SPEED. - double v_allowable = max_allowable_speed(-block->acceleration, MINIMUM_PLANNER_SPEED, block->millimeters); + float v_allowable = max_allowable_speed(-block->acceleration, MINIMUM_PLANNER_SPEED, block->millimeters); block->entry_speed = min(vmax_junction, v_allowable); // Initialize planner efficiency flags @@ -1051,43 +1292,47 @@ void Planner::check_axes_activity() { // block nominal speed limits both the current and next maximum junction speeds. Hence, in both // the reverse and forward planners, the corresponding block junction speed will always be at the // the maximum junction speed and may always be ignored for any speed reduction checks. - block->nominal_length_flag = (block->nominal_speed <= v_allowable); - block->recalculate_flag = true; // Always calculate trapezoid for new block + block->flag |= BLOCK_FLAG_RECALCULATE | (block->nominal_speed <= v_allowable ? BLOCK_FLAG_NOMINAL_LENGTH : 0); // Update previous path unit_vector and nominal speed - LOOP_XYZE(i) previous_speed[i] = current_speed[i]; + memcpy(previous_speed, current_speed, sizeof(previous_speed)); previous_nominal_speed = block->nominal_speed; + previous_safe_speed = safe_speed; #if ENABLED(LIN_ADVANCE) + // Don't use LIN_ADVANCE for blocks if: + // !block->steps[E_AXIS]: We don't have E steps todo (Travel move) + // !block->steps[X_AXIS] && !block->steps[Y_AXIS]: We don't have a movement in XY direction (Retract / Prime moves) + // extruder_advance_k == 0.0: There is no advance factor set // block->steps[E_AXIS] == block->step_event_count: A problem occurs when there's a very tiny move before a retract. // In this case, the retract and the move will be executed together. // This leads to an enormous number of advance steps due to a huge e_acceleration. // The math is correct, but you don't want a retract move done with advance! - // So this situation is filtered out here. - if (!block->steps[E_AXIS] || (!block->steps[X_AXIS] && !block->steps[Y_AXIS] && !block->steps[Z_AXIS]) || stepper.get_advance_k() == 0 || (uint32_t) block->steps[E_AXIS] == block->step_event_count) { + // de_float <= 0.0: Extruder is running in reverse direction (for example during "Wipe while retracting" (Slic3r) or "Combing" (Cura) movements) + if (!esteps || (!block->steps[X_AXIS] && !block->steps[Y_AXIS]) || extruder_advance_k == 0.0 || (uint32_t)esteps == block->step_event_count || de_float <= 0.0) { block->use_advance_lead = false; } else { block->use_advance_lead = true; - block->e_speed_multiplier8 = (block->steps[E_AXIS] << 8) / block->step_event_count; + block->abs_adv_steps_multiplier8 = lround(extruder_advance_k * (de_float / mm_D_float) * block->nominal_speed / (float)block->nominal_rate * axis_steps_per_mm[E_AXIS_N] * 256.0); } #elif ENABLED(ADVANCE) // Calculate advance rate - if (!block->steps[E_AXIS] || (!block->steps[X_AXIS] && !block->steps[Y_AXIS] && !block->steps[Z_AXIS])) { + if (!esteps || (!block->steps[X_AXIS] && !block->steps[Y_AXIS] && !block->steps[Z_AXIS])) { block->advance_rate = 0; block->advance = 0; } else { long acc_dist = estimate_acceleration_distance(0, block->nominal_rate, block->acceleration_steps_per_s2); - float advance = ((STEPS_PER_CUBIC_MM_E) * (EXTRUDER_ADVANCE_K)) * HYPOT(cse, EXTRUSION_AREA) * 256; + float advance = ((STEPS_PER_CUBIC_MM_E) * (EXTRUDER_ADVANCE_K)) * HYPOT(current_speed[E_AXIS], EXTRUSION_AREA) * 256; block->advance = advance; block->advance_rate = acc_dist ? advance / (float)acc_dist : 0; } /** - SERIAL_ECHO_START; + SERIAL_ECHO_START; SERIAL_ECHOPGM("advance :"); SERIAL_ECHO(block->advance/256.0); SERIAL_ECHOPGM("advance rate :"); @@ -1101,8 +1346,8 @@ void Planner::check_axes_activity() { // Move buffer head block_buffer_head = next_buffer_head; - // Update position - LOOP_XYZE(i) position[i] = target[i]; + // Update the position (only when a move was queued) + memcpy(position, target, sizeof(position)); recalculate(); @@ -1110,92 +1355,91 @@ void Planner::check_axes_activity() { } // buffer_line() -#if ENABLED(AUTO_BED_LEVELING_FEATURE) && DISABLED(DELTA) - - /** - * Get the XYZ position of the steppers as a vector_3. - * - * On CORE machines XYZ is derived from ABC. - */ - vector_3 Planner::adjusted_position() { - vector_3 pos = vector_3(stepper.get_axis_position_mm(X_AXIS), stepper.get_axis_position_mm(Y_AXIS), stepper.get_axis_position_mm(Z_AXIS)); - - //pos.debug("in Planner::adjusted_position"); - //bed_level_matrix.debug("in Planner::adjusted_position"); - - matrix_3x3 inverse = matrix_3x3::transpose(bed_level_matrix); - //inverse.debug("in Planner::inverse"); - - pos.apply_rotation(inverse); - //pos.debug("after rotation"); - - return pos; - } - -#endif // AUTO_BED_LEVELING_FEATURE && !DELTA - /** - * Directly set the planner XYZ position (hence the stepper positions). + * Directly set the planner XYZ position (and stepper positions) + * converting mm (or angles for SCARA) into steps. * * On CORE machines stepper ABC will be translated from the given XYZ. */ -#if ENABLED(AUTO_BED_LEVELING_FEATURE) || ENABLED(MESH_BED_LEVELING) - void Planner::set_position_mm(float x, float y, float z, const float& e) -#else - void Planner::set_position_mm(const float& x, const float& y, const float& z, const float& e) -#endif // AUTO_BED_LEVELING_FEATURE || MESH_BED_LEVELING - { - #if ENABLED(MESH_BED_LEVELING) - if (mbl.active()) - z += mbl.get_z(RAW_X_POSITION(x), RAW_Y_POSITION(y)); +void Planner::_set_position_mm(const float &a, const float &b, const float &c, const float &e) { + #if ENABLED(DISTINCT_E_FACTORS) + #define _EINDEX (E_AXIS + active_extruder) + last_extruder = active_extruder; + #else + #define _EINDEX E_AXIS + #endif + long na = position[X_AXIS] = lround(a * axis_steps_per_mm[X_AXIS]), + nb = position[Y_AXIS] = lround(b * axis_steps_per_mm[Y_AXIS]), + nc = position[Z_AXIS] = lround(c * axis_steps_per_mm[Z_AXIS]), + ne = position[E_AXIS] = lround(e * axis_steps_per_mm[_EINDEX]); + stepper.set_position(na, nb, nc, ne); + previous_nominal_speed = 0.0; // Resets planner junction speeds. Assumes start from rest. + ZERO(previous_speed); +} - #elif ENABLED(AUTO_BED_LEVELING_FEATURE) - - apply_rotation_xyz(bed_level_matrix, x, y, z); - - #endif - - long nx = position[X_AXIS] = lround(x * axis_steps_per_mm[X_AXIS]), - ny = position[Y_AXIS] = lround(y * axis_steps_per_mm[Y_AXIS]), - nz = position[Z_AXIS] = lround(z * axis_steps_per_mm[Z_AXIS]), - ne = position[E_AXIS] = lround(e * axis_steps_per_mm[E_AXIS]); - stepper.set_position(nx, ny, nz, ne); - previous_nominal_speed = 0.0; // Resets planner junction speeds. Assumes start from rest. - - LOOP_XYZE(i) previous_speed[i] = 0.0; - } +void Planner::set_position_mm_kinematic(const float position[NUM_AXIS]) { + #if PLANNER_LEVELING + float pos[XYZ] = { position[X_AXIS], position[Y_AXIS], position[Z_AXIS] }; + apply_leveling(pos); + #else + const float * const pos = position; + #endif + #if IS_KINEMATIC + inverse_kinematics(pos); + _set_position_mm(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], position[E_AXIS]); + #else + _set_position_mm(pos[X_AXIS], pos[Y_AXIS], pos[Z_AXIS], position[E_AXIS]); + #endif +} /** - * Directly set the planner E position (hence the stepper E position). + * Sync from the stepper positions. (e.g., after an interrupted move) */ -void Planner::set_e_position_mm(const float& e) { - position[E_AXIS] = lround(e * axis_steps_per_mm[E_AXIS]); - stepper.set_e_position(position[E_AXIS]); - previous_speed[E_AXIS] = 0.0; +void Planner::sync_from_steppers() { + LOOP_XYZE(i) position[i] = stepper.position((AxisEnum)i); +} + +/** + * Setters for planner position (also setting stepper position). + */ +void Planner::set_position_mm(const AxisEnum axis, const float& v) { + #if ENABLED(DISTINCT_E_FACTORS) + const uint8_t axis_index = axis + (axis == E_AXIS ? active_extruder : 0); + last_extruder = active_extruder; + #else + const uint8_t axis_index = axis; + #endif + position[axis] = lround(v * axis_steps_per_mm[axis_index]); + stepper.set_position(axis, v); + previous_speed[axis] = 0.0; } // Recalculate the steps/s^2 acceleration rates, based on the mm/s^2 void Planner::reset_acceleration_rates() { - LOOP_XYZE(i) + #if ENABLED(DISTINCT_E_FACTORS) + #define HIGHEST_CONDITION (i < E_AXIS || i == E_AXIS + active_extruder) + #else + #define HIGHEST_CONDITION true + #endif + uint32_t highest_rate = 1; + LOOP_XYZE_N(i) { max_acceleration_steps_per_s2[i] = max_acceleration_mm_per_s2[i] * axis_steps_per_mm[i]; + if (HIGHEST_CONDITION) NOLESS(highest_rate, max_acceleration_steps_per_s2[i]); + } + cutoff_long = 4294967295UL / highest_rate; } // Recalculate position, steps_to_mm if axis_steps_per_mm changes! void Planner::refresh_positioning() { - LOOP_XYZE(i) steps_to_mm[i] = 1.0 / axis_steps_per_mm[i]; - #if ENABLED(DELTA) || ENABLED(SCARA) - inverse_kinematics(current_position); - set_position_mm(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS]); - #else - set_position_mm(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); - #endif + LOOP_XYZE_N(i) steps_to_mm[i] = 1.0 / axis_steps_per_mm[i]; + set_position_mm_kinematic(current_position); reset_acceleration_rates(); } #if ENABLED(AUTOTEMP) - void Planner::autotemp_M109() { + void Planner::autotemp_M104_M109() { autotemp_enabled = code_seen('F'); if (autotemp_enabled) autotemp_factor = code_value_temp_diff(); if (code_seen('S')) autotemp_min = code_value_temp_abs(); @@ -1203,3 +1447,14 @@ void Planner::refresh_positioning() { } #endif + +#if ENABLED(LIN_ADVANCE) + + void Planner::advance_M905(const float &k) { + if (k >= 0.0) extruder_advance_k = k; + SERIAL_ECHO_START; + SERIAL_ECHOPAIR("Advance factor: ", extruder_advance_k); + SERIAL_EOL; + } + +#endif diff --git a/Marlin/planner.h b/Marlin/planner.h index 740553668a..9ba2e69f3a 100644 --- a/Marlin/planner.h +++ b/Marlin/planner.h @@ -33,14 +33,35 @@ #define PLANNER_H #include "types.h" -#include "MarlinConfig.h" +#include "enum.h" +#include "Marlin.h" -#if ENABLED(AUTO_BED_LEVELING_FEATURE) +#if HAS_ABL #include "vector_3.h" #endif -class Planner; -extern Planner planner; +enum BlockFlagBit { + // Recalculate trapezoids on entry junction. For optimization. + BLOCK_BIT_RECALCULATE, + + // Nominal speed always reached. + // i.e., The segment is long enough, so the nominal speed is reachable if accelerating + // from a safe speed (in consideration of jerking from zero speed). + BLOCK_BIT_NOMINAL_LENGTH, + + // Start from a halt at the start of this block, respecting the maximum allowed jerk. + BLOCK_BIT_START_FROM_FULL_HALT, + + // The block is busy + BLOCK_BIT_BUSY +}; + +enum BlockFlag { + BLOCK_FLAG_RECALCULATE = _BV(BLOCK_BIT_RECALCULATE), + BLOCK_FLAG_NOMINAL_LENGTH = _BV(BLOCK_BIT_NOMINAL_LENGTH), + BLOCK_FLAG_START_FROM_FULL_HALT = _BV(BLOCK_BIT_START_FROM_FULL_HALT), + BLOCK_FLAG_BUSY = _BV(BLOCK_BIT_BUSY) +}; /** * struct block_t @@ -53,57 +74,59 @@ extern Planner planner; */ typedef struct { + uint8_t flag; // Block flags (See BlockFlag enum above) + unsigned char active_extruder; // The extruder to move (if E move) - // Fields used by the bresenham algorithm for tracing the line - long steps[NUM_AXIS]; // Step count along each axis - unsigned long step_event_count; // The number of step events required to complete this block + // Fields used by the Bresenham algorithm for tracing the line + int32_t steps[NUM_AXIS]; // Step count along each axis + uint32_t step_event_count; // The number of step events required to complete this block #if ENABLED(MIXING_EXTRUDER) - unsigned long mix_event_count[MIXING_STEPPERS]; // Scaled step_event_count for the mixing steppers + uint32_t mix_event_count[MIXING_STEPPERS]; // Scaled step_event_count for the mixing steppers #endif - long accelerate_until, // The index of the step event on which to stop acceleration - decelerate_after, // The index of the step event on which to start decelerating - acceleration_rate; // The acceleration rate used for acceleration calculation + int32_t accelerate_until, // The index of the step event on which to stop acceleration + decelerate_after, // The index of the step event on which to start decelerating + acceleration_rate; // The acceleration rate used for acceleration calculation - unsigned char direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h) + uint8_t direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h) // Advance extrusion #if ENABLED(LIN_ADVANCE) bool use_advance_lead; - int e_speed_multiplier8; // Factorised by 2^8 to avoid float + uint32_t abs_adv_steps_multiplier8; // Factorised by 2^8 to avoid float #elif ENABLED(ADVANCE) - long advance_rate; - volatile long initial_advance; - volatile long final_advance; + int32_t advance_rate; + volatile int32_t initial_advance; + volatile int32_t final_advance; float advance; #endif // Fields used by the motion planner to manage acceleration - float nominal_speed, // The nominal speed for this block in mm/sec - entry_speed, // Entry speed at previous-current junction in mm/sec - max_entry_speed, // Maximum allowable junction entry speed in mm/sec - millimeters, // The total travel of this block in mm - acceleration; // acceleration mm/sec^2 - unsigned char recalculate_flag, // Planner flag to recalculate trapezoids on entry junction - nominal_length_flag; // Planner flag for nominal speed always reached + float nominal_speed, // The nominal speed for this block in mm/sec + entry_speed, // Entry speed at previous-current junction in mm/sec + max_entry_speed, // Maximum allowable junction entry speed in mm/sec + millimeters, // The total travel of this block in mm + acceleration; // acceleration mm/sec^2 // Settings for the trapezoid generator - unsigned long nominal_rate, // The nominal step rate for this block in step_events/sec - initial_rate, // The jerk-adjusted step rate at start of block - final_rate, // The minimal rate at exit - acceleration_steps_per_s2; // acceleration steps/sec^2 + uint32_t nominal_rate, // The nominal step rate for this block in step_events/sec + initial_rate, // The jerk-adjusted step rate at start of block + final_rate, // The minimal rate at exit + acceleration_steps_per_s2; // acceleration steps/sec^2 #if FAN_COUNT > 0 - unsigned long fan_speed[FAN_COUNT]; + uint16_t fan_speed[FAN_COUNT]; #endif #if ENABLED(BARICUDA) - unsigned long valve_pressure, e_to_p_pressure; + uint32_t valve_pressure, e_to_p_pressure; + #endif + + #if ENABLED(ENSURE_SMOOTH_MOVES) + uint32_t segment_time; #endif - - volatile char busy; } block_t; @@ -117,29 +140,36 @@ class Planner { * A ring buffer of moves described in steps */ static block_t block_buffer[BLOCK_BUFFER_SIZE]; - static volatile uint8_t block_buffer_head; // Index of the next block to be pushed - static volatile uint8_t block_buffer_tail; + static volatile uint8_t block_buffer_head, // Index of the next block to be pushed + block_buffer_tail; - static float max_feedrate_mm_s[NUM_AXIS]; // Max speeds in mm per second - static float axis_steps_per_mm[NUM_AXIS]; - static float steps_to_mm[NUM_AXIS]; - static unsigned long max_acceleration_steps_per_s2[NUM_AXIS]; - static unsigned long max_acceleration_mm_per_s2[NUM_AXIS]; // Use M201 to override by software + #if ENABLED(DISTINCT_E_FACTORS) + static uint8_t last_extruder; // Respond to extruder change + #endif + + static float max_feedrate_mm_s[XYZE_N], // Max speeds in mm per second + axis_steps_per_mm[XYZE_N], + steps_to_mm[XYZE_N]; + static unsigned long max_acceleration_steps_per_s2[XYZE_N], + max_acceleration_mm_per_s2[XYZE_N]; // Use M201 to override by software static millis_t min_segment_time; - static float min_feedrate_mm_s; - static float acceleration; // Normal acceleration mm/s^2 DEFAULT ACCELERATION for all printing moves. M204 SXXXX - static float retract_acceleration; // Retract acceleration mm/s^2 filament pull-back and push-forward while standing still in the other axes M204 TXXXX - static float travel_acceleration; // Travel acceleration mm/s^2 DEFAULT ACCELERATION for all NON printing moves. M204 MXXXX - static float max_xy_jerk; // The largest speed change requiring no acceleration - static float max_z_jerk; - static float max_e_jerk; - static float min_travel_feedrate_mm_s; + static float min_feedrate_mm_s, + acceleration, // Normal acceleration mm/s^2 DEFAULT ACCELERATION for all printing moves. M204 SXXXX + retract_acceleration, // Retract acceleration mm/s^2 filament pull-back and push-forward while standing still in the other axes M204 TXXXX + travel_acceleration, // Travel acceleration mm/s^2 DEFAULT ACCELERATION for all NON printing moves. M204 MXXXX + max_jerk[XYZE], // The largest speed change requiring no acceleration + min_travel_feedrate_mm_s; - #if ENABLED(AUTO_BED_LEVELING_FEATURE) + #if HAS_ABL + static bool abl_enabled; // Flag that bed leveling is enabled static matrix_3x3 bed_level_matrix; // Transform to compensate for bed level #endif + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + static float z_fade_height, inverse_z_fade_height; + #endif + private: /** @@ -157,6 +187,11 @@ class Planner { * Nominal speed of previous path line segment */ static float previous_nominal_speed; + + /** + * Limit where 64bit math is necessary for acceleration calculation + */ + static uint32_t cutoff_long; #if ENABLED(DISABLE_INACTIVE_EXTRUDER) /** @@ -173,6 +208,15 @@ class Planner { // Segment times (in µs). Used for speed calculations static long axis_segment_time[2][3]; #endif + + #if ENABLED(LIN_ADVANCE) + static float position_float[NUM_AXIS]; + static float extruder_advance_k; + #endif + + #if ENABLED(ENSURE_SMOOTH_MOVES) + static uint32_t block_buffer_runtime_us; //Theoretical block buffer runtime in µs + #endif public: @@ -201,46 +245,120 @@ class Planner { static bool is_full() { return (block_buffer_tail == BLOCK_MOD(block_buffer_head + 1)); } - #if ENABLED(AUTO_BED_LEVELING_FEATURE) || ENABLED(MESH_BED_LEVELING) + #if PLANNER_LEVELING - #if ENABLED(AUTO_BED_LEVELING_FEATURE) - /** - * The corrected position, applying the bed level matrix - */ - static vector_3 adjusted_position(); - #endif + #define ARG_X float lx + #define ARG_Y float ly + #define ARG_Z float lz /** - * Add a new linear movement to the buffer. - * - * x,y,z,e - target position in mm - * fr_mm_s - (target) speed of the move (mm/s) - * extruder - target extruder + * Apply leveling to transform a cartesian position + * as it will be given to the planner and steppers. */ - static void buffer_line(float x, float y, float z, const float& e, float fr_mm_s, const uint8_t extruder); - - /** - * Set the planner.position and individual stepper positions. - * Used by G92, G28, G29, and other procedures. - * - * Multiplies by axis_steps_per_mm[] and does necessary conversion - * for COREXY / COREXZ / COREYZ to set the corresponding stepper positions. - * - * Clears previous speed values. - */ - static void set_position_mm(float x, float y, float z, const float& e); + static void apply_leveling(float &lx, float &ly, float &lz); + static void apply_leveling(float logical[XYZ]) { apply_leveling(logical[X_AXIS], logical[Y_AXIS], logical[Z_AXIS]); } + static void unapply_leveling(float logical[XYZ]); #else - static void buffer_line(const float& x, const float& y, const float& z, const float& e, float fr_mm_s, const uint8_t extruder); - static void set_position_mm(const float& x, const float& y, const float& z, const float& e); + #define ARG_X const float &lx + #define ARG_Y const float &ly + #define ARG_Z const float &lz - #endif // AUTO_BED_LEVELING_FEATURE || MESH_BED_LEVELING + #endif + + #if ENABLED(LIN_ADVANCE) + void advance_M905(const float &k); + #endif /** - * Set the E position (mm) of the planner (and the E stepper) + * Planner::_buffer_line + * + * Add a new direct linear movement to the buffer. + * + * Leveling and kinematics should be applied ahead of this. + * + * a,b,c,e - target position in mm or degrees + * fr_mm_s - (target) speed of the move (mm/s) + * extruder - target extruder */ - static void set_e_position_mm(const float& e); + static void _buffer_line(const float &a, const float &b, const float &c, const float &e, float fr_mm_s, const uint8_t extruder); + + static void _set_position_mm(const float &a, const float &b, const float &c, const float &e); + + /** + * Add a new linear movement to the buffer. + * The target is NOT translated to delta/scara + * + * Leveling will be applied to input on cartesians. + * Kinematic machines should call buffer_line_kinematic (for leveled moves). + * (Cartesians may also call buffer_line_kinematic.) + * + * lx,ly,lz,e - target position in mm or degrees + * fr_mm_s - (target) speed of the move (mm/s) + * extruder - target extruder + */ + static FORCE_INLINE void buffer_line(ARG_X, ARG_Y, ARG_Z, const float &e, const float &fr_mm_s, const uint8_t extruder) { + #if PLANNER_LEVELING && IS_CARTESIAN + apply_leveling(lx, ly, lz); + #endif + _buffer_line(lx, ly, lz, e, fr_mm_s, extruder); + } + + /** + * Add a new linear movement to the buffer. + * The target is cartesian, it's translated to delta/scara if + * needed. + * + * target - x,y,z,e CARTESIAN target in mm + * fr_mm_s - (target) speed of the move (mm/s) + * extruder - target extruder + */ + static FORCE_INLINE void buffer_line_kinematic(const float target[XYZE], const float &fr_mm_s, const uint8_t extruder) { + #if PLANNER_LEVELING + float pos[XYZ] = { target[X_AXIS], target[Y_AXIS], target[Z_AXIS] }; + apply_leveling(pos); + #else + const float * const pos = target; + #endif + #if IS_KINEMATIC + inverse_kinematics(pos); + _buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], target[E_AXIS], fr_mm_s, extruder); + #else + _buffer_line(pos[X_AXIS], pos[Y_AXIS], pos[Z_AXIS], target[E_AXIS], fr_mm_s, extruder); + #endif + } + + /** + * Set the planner.position and individual stepper positions. + * Used by G92, G28, G29, and other procedures. + * + * Multiplies by axis_steps_per_mm[] and does necessary conversion + * for COREXY / COREXZ / COREYZ to set the corresponding stepper positions. + * + * Clears previous speed values. + */ + static FORCE_INLINE void set_position_mm(ARG_X, ARG_Y, ARG_Z, const float &e) { + #if PLANNER_LEVELING && IS_CARTESIAN + apply_leveling(lx, ly, lz); + #endif + _set_position_mm(lx, ly, lz, e); + } + static void set_position_mm_kinematic(const float position[NUM_AXIS]); + static void set_position_mm(const AxisEnum axis, const float &v); + static FORCE_INLINE void set_z_position_mm(const float &z) { set_position_mm(Z_AXIS, z); } + static FORCE_INLINE void set_e_position_mm(const float &e) { + set_position_mm(E_AXIS + #if ENABLED(DISTINCT_E_FACTORS) + + active_extruder + #endif + , e); + } + + /** + * Sync from the stepper positions. (e.g., after an interrupted move) + */ + static void sync_from_steppers(); /** * Does the buffer have any blocks queued? @@ -263,20 +381,37 @@ class Planner { static block_t* get_current_block() { if (blocks_queued()) { block_t* block = &block_buffer[block_buffer_tail]; - block->busy = true; + #if ENABLED(ENSURE_SMOOTH_MOVES) + block_buffer_runtime_us -= block->segment_time; //We can't be sure how long an active block will take, so don't count it. + #endif + SBI(block->flag, BLOCK_BIT_BUSY); return block; } else return NULL; } + #if ENABLED(ENSURE_SMOOTH_MOVES) + static bool long_move() { + if (blocks_queued()) { + return block_buffer_runtime_us > (LCD_UPDATE_THRESHOLD) * 1000UL + (MIN_BLOCK_TIME) * 3000UL; + } + else + return true; + } + + static void clear_block_buffer_runtime(){ + block_buffer_runtime_us = 0; + } + #endif + #if ENABLED(AUTOTEMP) static float autotemp_max; static float autotemp_min; static float autotemp_factor; static bool autotemp_enabled; static void getHighESpeed(); - static void autotemp_M109(); + static void autotemp_M104_M109(); #endif private: @@ -291,7 +426,7 @@ class Planner { * Calculate the distance (not time) it takes to accelerate * from initial_rate to target_rate using the given acceleration: */ - static float estimate_acceleration_distance(float initial_rate, float target_rate, float accel) { + static float estimate_acceleration_distance(const float &initial_rate, const float &target_rate, const float &accel) { if (accel == 0) return 0; // accel was 0, set acceleration distance to 0 return (sq(target_rate) - sq(initial_rate)) / (accel * 2); } @@ -304,7 +439,7 @@ class Planner { * This is used to compute the intersection point between acceleration and deceleration * in cases where the "trapezoid" has no plateau (i.e., never reaches maximum speed) */ - static float intersection_distance(float initial_rate, float final_rate, float accel, float distance) { + static float intersection_distance(const float &initial_rate, const float &final_rate, const float &accel, const float &distance) { if (accel == 0) return 0; // accel was 0, set intersection distance to 0 return (accel * 2 * distance - sq(initial_rate) + sq(final_rate)) / (accel * 4); } @@ -314,14 +449,14 @@ class Planner { * to reach 'target_velocity' using 'acceleration' within a given * 'distance'. */ - static float max_allowable_speed(float accel, float target_velocity, float distance) { + static float max_allowable_speed(const float &accel, const float &target_velocity, const float &distance) { return sqrt(sq(target_velocity) - 2 * accel * distance); } - static void calculate_trapezoid_for_block(block_t* block, float entry_factor, float exit_factor); + static void calculate_trapezoid_for_block(block_t* const block, const float &entry_factor, const float &exit_factor); - static void reverse_pass_kernel(block_t* previous, block_t* current, block_t* next); - static void forward_pass_kernel(block_t* previous, block_t* current, block_t* next); + static void reverse_pass_kernel(block_t* const current, const block_t *next); + static void forward_pass_kernel(const block_t *previous, block_t* const current); static void reverse_pass(); static void forward_pass(); @@ -332,4 +467,6 @@ class Planner { }; +extern Planner planner; + #endif // PLANNER_H diff --git a/Marlin/planner_bezier.cpp b/Marlin/planner_bezier.cpp index 6ca7afd1d6..d7dd960900 100644 --- a/Marlin/planner_bezier.cpp +++ b/Marlin/planner_bezier.cpp @@ -187,16 +187,7 @@ void cubic_b_spline(const float position[NUM_AXIS], const float target[NUM_AXIS] bez_target[Z_AXIS] = interp(position[Z_AXIS], target[Z_AXIS], t); bez_target[E_AXIS] = interp(position[E_AXIS], target[E_AXIS], t); clamp_to_software_endstops(bez_target); - - #if ENABLED(DELTA) || ENABLED(SCARA) - inverse_kinematics(bez_target); - #if ENABLED(DELTA) && ENABLED(AUTO_BED_LEVELING_FEATURE) - adjust_delta(bez_target); - #endif - planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], bez_target[E_AXIS], fr_mm_s, extruder); - #else - planner.buffer_line(bez_target[X_AXIS], bez_target[Y_AXIS], bez_target[Z_AXIS], bez_target[E_AXIS], fr_mm_s, extruder); - #endif + planner.buffer_line_kinematic(bez_target, fr_mm_s, extruder); } } diff --git a/Marlin/platformio.ini b/Marlin/platformio.ini new file mode 100755 index 0000000000..a00864659d --- /dev/null +++ b/Marlin/platformio.ini @@ -0,0 +1,53 @@ +# +# Project Configuration File +# +# A detailed documentation with the EXAMPLES is located here: +# http://docs.platformio.org/en/latest/projectconf.html +# + +# A sign `#` at the beginning of the line indicates a comment +# Comment lines are ignored. + +# Automatic targets - enable auto-uploading +# targets = upload + +[platformio] +src_dir = ./ +envs_dir = ../.pioenvs +lib_dir = ../.piolib +env_default = mega2560 + +[env:mega2560] +platform = atmelavr +framework = arduino +board = megaatmega2560 +build_flags = -I $BUILDSRC_DIR +board_f_cpu = 16000000L + +[env:mega1280] +platform = atmelavr +framework = arduino +board = megaatmega1280 +build_flags = -I $BUILDSRC_DIR +board_f_cpu = 16000000L + +[env:printrboard] +platform = teensy +framework = arduino +board = teensy20pp +build_flags = -I $BUILDSRC_DIR -D MOTHERBOARD=BOARD_PRINTRBOARD +# Bug in arduino framework does not allow boards running at 20Mhz +#board_f_cpu = 20000000L + +[env:brainwavepro] +platform = teensy +framework = arduino +board = teensy20pp +build_flags = -I $BUILDSRC_DIR -D MOTHERBOARD=BOARD_BRAINWAVE_PRO -D AT90USBxx_TEENSYPP_ASSIGNMENTS + +[env:rambo] +platform = atmelavr +framework = arduino +board = reprap_rambo +build_flags = -I $BUILDSRC_DIR +board_f_cpu = 16000000L diff --git a/Marlin/qr_solve.cpp b/Marlin/qr_solve.cpp index ddafb005ea..20bbb62994 100644 --- a/Marlin/qr_solve.cpp +++ b/Marlin/qr_solve.cpp @@ -22,7 +22,7 @@ #include "qr_solve.h" -#if ENABLED(AUTO_BED_LEVELING_GRID) +#if ENABLED(AUTO_BED_LEVELING_LINEAR) #include #include @@ -59,7 +59,7 @@ int i4_min(int i1, int i2) return (i1 < i2) ? i1 : i2; } -double r8_epsilon(void) +float r8_epsilon(void) /******************************************************************************/ /** @@ -89,14 +89,14 @@ double r8_epsilon(void) Parameters: - Output, double R8_EPSILON, the R8 round-off unit. + Output, float R8_EPSILON, the R8 round-off unit. */ { - const double value = 2.220446049250313E-016; + const float value = 2.220446049250313E-016; return value; } -double r8_max(double x, double y) +float r8_max(float x, float y) /******************************************************************************/ /** @@ -118,15 +118,15 @@ double r8_max(double x, double y) Parameters: - Input, double X, Y, the quantities to compare. + Input, float X, Y, the quantities to compare. - Output, double R8_MAX, the maximum of X and Y. + Output, float R8_MAX, the maximum of X and Y. */ { return (y < x) ? x : y; } -double r8_abs(double x) +float r8_abs(float x) /******************************************************************************/ /** @@ -148,15 +148,15 @@ double r8_abs(double x) Parameters: - Input, double X, the quantity whose absolute value is desired. + Input, float X, the quantity whose absolute value is desired. - Output, double R8_ABS, the absolute value of X. + Output, float R8_ABS, the absolute value of X. */ { return (x < 0.0) ? -x : x; } -double r8_sign(double x) +float r8_sign(float x) /******************************************************************************/ /** @@ -178,15 +178,15 @@ double r8_sign(double x) Parameters: - Input, double X, the number whose sign is desired. + Input, float X, the number whose sign is desired. - Output, double R8_SIGN, the sign of X. + Output, float R8_SIGN, the sign of X. */ { return (x < 0.0) ? -1.0 : 1.0; } -double r8mat_amax(int m, int n, double a[]) +float r8mat_amax(int m, int n, float a[]) /******************************************************************************/ /** @@ -217,12 +217,12 @@ double r8mat_amax(int m, int n, double a[]) Input, int N, the number of columns in A. - Input, double A[M*N], the M by N matrix. + Input, float A[M*N], the M by N matrix. - Output, double R8MAT_AMAX, the maximum absolute value entry of A. + Output, float R8MAT_AMAX, the maximum absolute value entry of A. */ { - double value = r8_abs(a[0 + 0 * m]); + float value = r8_abs(a[0 + 0 * m]); for (int j = 0; j < n; j++) { for (int i = 0; i < m; i++) { NOLESS(value, r8_abs(a[i + j * m])); @@ -231,7 +231,7 @@ double r8mat_amax(int m, int n, double a[]) return value; } -void r8mat_copy(double a2[], int m, int n, double a1[]) +void r8mat_copy(float a2[], int m, int n, float a1[]) /******************************************************************************/ /** @@ -260,9 +260,9 @@ void r8mat_copy(double a2[], int m, int n, double a1[]) Input, int M, N, the number of rows and columns. - Input, double A1[M*N], the matrix to be copied. + Input, float A1[M*N], the matrix to be copied. - Output, double R8MAT_COPY_NEW[M*N], the copy of A1. + Output, float R8MAT_COPY_NEW[M*N], the copy of A1. */ { for (int j = 0; j < n; j++) { @@ -273,7 +273,7 @@ void r8mat_copy(double a2[], int m, int n, double a1[]) /******************************************************************************/ -void daxpy(int n, double da, double dx[], int incx, double dy[], int incy) +void daxpy(int n, float da, float dx[], int incx, float dy[], int incy) /******************************************************************************/ /** @@ -313,13 +313,13 @@ void daxpy(int n, double da, double dx[], int incx, double dy[], int incy) Input, int N, the number of elements in DX and DY. - Input, double DA, the multiplier of DX. + Input, float DA, the multiplier of DX. - Input, double DX[*], the first vector. + Input, float DX[*], the first vector. Input, int INCX, the increment between successive entries of DX. - Input/output, double DY[*], the second vector. + Input/output, float DY[*], the second vector. On output, DY[*] has been replaced by DY[*] + DA * DX[*]. Input, int INCY, the increment between successive entries of DY. @@ -364,7 +364,7 @@ void daxpy(int n, double da, double dx[], int incx, double dy[], int incy) } /******************************************************************************/ -double ddot(int n, double dx[], int incx, double dy[], int incy) +float ddot(int n, float dx[], int incx, float dy[], int incy) /******************************************************************************/ /** @@ -404,15 +404,15 @@ double ddot(int n, double dx[], int incx, double dy[], int incy) Input, int N, the number of entries in the vectors. - Input, double DX[*], the first vector. + Input, float DX[*], the first vector. Input, int INCX, the increment between successive entries in DX. - Input, double DY[*], the second vector. + Input, float DY[*], the second vector. Input, int INCY, the increment between successive entries in DY. - Output, double DDOT, the sum of the product of the corresponding + Output, float DDOT, the sum of the product of the corresponding entries of DX and DY. */ { @@ -420,7 +420,7 @@ double ddot(int n, double dx[], int incx, double dy[], int incy) if (n <= 0) return 0.0; int i, m; - double dtemp = 0.0; + float dtemp = 0.0; /** Code for unequal increments or equal increments @@ -454,7 +454,7 @@ double ddot(int n, double dx[], int incx, double dy[], int incy) } /******************************************************************************/ -double dnrm2(int n, double x[], int incx) +float dnrm2(int n, float x[], int incx) /******************************************************************************/ /** @@ -494,24 +494,24 @@ double dnrm2(int n, double x[], int incx) Input, int N, the number of entries in the vector. - Input, double X[*], the vector whose norm is to be computed. + Input, float X[*], the vector whose norm is to be computed. Input, int INCX, the increment between successive entries of X. - Output, double DNRM2, the Euclidean norm of X. + Output, float DNRM2, the Euclidean norm of X. */ { - double norm; + float norm; if (n < 1 || incx < 1) norm = 0.0; else if (n == 1) norm = r8_abs(x[0]); else { - double scale = 0.0, ssq = 1.0; + float scale = 0.0, ssq = 1.0; int ix = 0; for (int i = 0; i < n; i++) { if (x[ix] != 0.0) { - double absxi = r8_abs(x[ix]); + float absxi = r8_abs(x[ix]); if (scale < absxi) { ssq = 1.0 + ssq * (scale / absxi) * (scale / absxi); scale = absxi; @@ -527,8 +527,8 @@ double dnrm2(int n, double x[], int incx) } /******************************************************************************/ -void dqrank(double a[], int lda, int m, int n, double tol, int* kr, - int jpvt[], double qraux[]) +void dqrank(float a[], int lda, int m, int n, float tol, int* kr, + int jpvt[], float qraux[]) /******************************************************************************/ /** @@ -572,7 +572,7 @@ void dqrank(double a[], int lda, int m, int n, double tol, int* kr, Parameters: - Input/output, double A[LDA*N]. On input, the matrix whose + Input/output, float A[LDA*N]. On input, the matrix whose decomposition is to be computed. On output, the information from DQRDC. The triangular matrix R of the QR factorization is contained in the upper triangle and information needed to recover the orthogonal @@ -585,7 +585,7 @@ void dqrank(double a[], int lda, int m, int n, double tol, int* kr, Input, int N, the number of columns of A. - Input, double TOL, a relative tolerance used to determine the + Input, float TOL, a relative tolerance used to determine the numerical rank. The problem should be scaled so that all the elements of A have roughly the same absolute accuracy, EPS. Then a reasonable value for TOL is roughly EPS divided by the magnitude of the largest @@ -598,11 +598,11 @@ void dqrank(double a[], int lda, int m, int n, double tol, int* kr, independent to within the tolerance TOL and the remaining columns are linearly dependent. - Output, double QRAUX[N], will contain extra information defining + Output, float QRAUX[N], will contain extra information defining the QR factorization. */ { - double work[n]; + float work[n]; for (int i = 0; i < n; i++) jpvt[i] = 0; @@ -621,8 +621,8 @@ void dqrank(double a[], int lda, int m, int n, double tol, int* kr, } /******************************************************************************/ -void dqrdc(double a[], int lda, int n, int p, double qraux[], int jpvt[], - double work[], int job) +void dqrdc(float a[], int lda, int n, int p, float qraux[], int jpvt[], + float work[], int job) /******************************************************************************/ /** @@ -660,7 +660,7 @@ void dqrdc(double a[], int lda, int n, int p, double qraux[], int jpvt[], Parameters: - Input/output, double A(LDA,P). On input, the N by P matrix + Input/output, float A(LDA,P). On input, the N by P matrix whose decomposition is to be computed. On output, A contains in its upper triangle the upper triangular matrix R of the QR factorization. Below its diagonal A contains information from @@ -676,7 +676,7 @@ void dqrdc(double a[], int lda, int n, int p, double qraux[], int jpvt[], Input, int P, the number of columns of the matrix A. - Output, double QRAUX[P], contains further information required + Output, float QRAUX[P], contains further information required to recover the orthogonal part of the decomposition. Input/output, integer JPVT[P]. On input, JPVT contains integers that @@ -695,7 +695,7 @@ void dqrdc(double a[], int lda, int n, int p, double qraux[], int jpvt[], original matrix that has been interchanged into the K-th column, if pivoting was requested. - Workspace, double WORK[P]. WORK is not referenced if JOB == 0. + Workspace, float WORK[P]. WORK is not referenced if JOB == 0. Input, int JOB, initiates column pivoting. 0, no pivoting is done. @@ -706,7 +706,7 @@ void dqrdc(double a[], int lda, int n, int p, double qraux[], int jpvt[], int j; int lup; int maxj; - double maxnrm, nrmxl, t, tt; + float maxnrm, nrmxl, t, tt; int pl = 1, pu = 0; /** @@ -815,8 +815,8 @@ void dqrdc(double a[], int lda, int n, int p, double qraux[], int jpvt[], } /******************************************************************************/ -int dqrls(double a[], int lda, int m, int n, double tol, int* kr, double b[], - double x[], double rsd[], int jpvt[], double qraux[], int itask) +int dqrls(float a[], int lda, int m, int n, float tol, int* kr, float b[], + float x[], float rsd[], int jpvt[], float qraux[], int itask) /******************************************************************************/ /** @@ -871,7 +871,7 @@ int dqrls(double a[], int lda, int m, int n, double tol, int* kr, double b[], Parameters: - Input/output, double A[LDA*N], an M by N matrix. + Input/output, float A[LDA*N], an M by N matrix. On input, the matrix whose decomposition is to be computed. In a least squares data fitting problem, A(I,J) is the value of the J-th basis (model) function at the I-th data point. @@ -886,7 +886,7 @@ int dqrls(double a[], int lda, int m, int n, double tol, int* kr, double b[], Input, int N, the number of columns of A. - Input, double TOL, a relative tolerance used to determine the + Input, float TOL, a relative tolerance used to determine the numerical rank. The problem should be scaled so that all the elements of A have roughly the same absolute accuracy EPS. Then a reasonable value for TOL is roughly EPS divided by the magnitude of the largest @@ -894,12 +894,12 @@ int dqrls(double a[], int lda, int m, int n, double tol, int* kr, double b[], Output, int *KR, the numerical rank. - Input, double B[M], the right hand side of the linear system. + Input, float B[M], the right hand side of the linear system. - Output, double X[N], a least squares solution to the linear + Output, float X[N], a least squares solution to the linear system. - Output, double RSD[M], the residual, B - A*X. RSD may + Output, float RSD[M], the residual, B - A*X. RSD may overwrite B. Workspace, int JPVT[N], required if ITASK = 1. @@ -909,7 +909,7 @@ int dqrls(double a[], int lda, int m, int n, double tol, int* kr, double b[], of the condition number of the matrix of independent columns, and of R. This estimate will be <= 1/TOL. - Workspace, double QRAUX[N], required if ITASK = 1. + Workspace, float QRAUX[N], required if ITASK = 1. Input, int ITASK. 1, DQRLS factors the matrix A and solves the least squares problem. @@ -962,8 +962,8 @@ int dqrls(double a[], int lda, int m, int n, double tol, int* kr, double b[], } /******************************************************************************/ -void dqrlss(double a[], int lda, int m, int n, int kr, double b[], double x[], - double rsd[], int jpvt[], double qraux[]) +void dqrlss(float a[], int lda, int m, int n, int kr, float b[], float x[], + float rsd[], int jpvt[], float qraux[]) /******************************************************************************/ /** @@ -1004,7 +1004,7 @@ void dqrlss(double a[], int lda, int m, int n, int kr, double b[], double x[], Parameters: - Input, double A[LDA*N], the QR factorization information + Input, float A[LDA*N], the QR factorization information from DQRANK. The triangular matrix R of the QR factorization is contained in the upper triangle and information needed to recover the orthogonal matrix Q is stored below the diagonal in A and in @@ -1019,12 +1019,12 @@ void dqrlss(double a[], int lda, int m, int n, int kr, double b[], double x[], Input, int KR, the rank of the matrix, as estimated by DQRANK. - Input, double B[M], the right hand side of the linear system. + Input, float B[M], the right hand side of the linear system. - Output, double X[N], a least squares solution to the + Output, float X[N], a least squares solution to the linear system. - Output, double RSD[M], the residual, B - A*X. RSD may + Output, float RSD[M], the residual, B - A*X. RSD may overwrite B. Input, int JPVT[N], the pivot information from DQRANK. @@ -1032,7 +1032,7 @@ void dqrlss(double a[], int lda, int m, int n, int kr, double b[], double x[], independent to within the tolerance TOL and the remaining columns are linearly dependent. - Input, double QRAUX[N], auxiliary information from DQRANK + Input, float QRAUX[N], auxiliary information from DQRANK defining the QR factorization. */ { @@ -1041,7 +1041,7 @@ void dqrlss(double a[], int lda, int m, int n, int kr, double b[], double x[], int j; int job; int k; - double t; + float t; if (kr != 0) { job = 110; @@ -1071,8 +1071,8 @@ void dqrlss(double a[], int lda, int m, int n, int kr, double b[], double x[], } /******************************************************************************/ -int dqrsl(double a[], int lda, int n, int k, double qraux[], double y[], - double qy[], double qty[], double b[], double rsd[], double ab[], int job) +int dqrsl(float a[], int lda, int n, int k, float qraux[], float y[], + float qy[], float qty[], float b[], float rsd[], float ab[], int job) /******************************************************************************/ /** @@ -1158,7 +1158,7 @@ int dqrsl(double a[], int lda, int n, int k, double qraux[], double y[], Parameters: - Input, double A[LDA*P], contains the output of DQRDC. + Input, float A[LDA*P], contains the output of DQRDC. Input, int LDA, the leading dimension of the array A. @@ -1169,26 +1169,26 @@ int dqrsl(double a[], int lda, int n, int k, double qraux[], double y[], must not be greater than min(N,P), where P is the same as in the calling sequence to DQRDC. - Input, double QRAUX[P], the auxiliary output from DQRDC. + Input, float QRAUX[P], the auxiliary output from DQRDC. - Input, double Y[N], a vector to be manipulated by DQRSL. + Input, float Y[N], a vector to be manipulated by DQRSL. - Output, double QY[N], contains Q * Y, if requested. + Output, float QY[N], contains Q * Y, if requested. - Output, double QTY[N], contains Q' * Y, if requested. + Output, float QTY[N], contains Q' * Y, if requested. - Output, double B[K], the solution of the least squares problem + Output, float B[K], the solution of the least squares problem minimize norm2 ( Y - AK * B), if its computation has been requested. Note that if pivoting was requested in DQRDC, the J-th component of B will be associated with column JPVT(J) of the original matrix A that was input into DQRDC. - Output, double RSD[N], the least squares residual Y - AK * B, + Output, float RSD[N], the least squares residual Y - AK * B, if its computation has been requested. RSD is also the orthogonal projection of Y onto the orthogonal complement of the column space of AK. - Output, double AB[N], the least squares approximation Ak * B, + Output, float AB[N], the least squares approximation Ak * B, if its computation has been requested. AB is also the orthogonal projection of Y onto the column space of A. @@ -1220,8 +1220,8 @@ int dqrsl(double a[], int lda, int n, int k, double qraux[], double y[], int j; int jj; int ju; - double t; - double temp; + float t; + float temp; /** Set INFO flag. */ @@ -1366,7 +1366,7 @@ int dqrsl(double a[], int lda, int n, int k, double qraux[], double y[], /******************************************************************************/ -void dscal(int n, double sa, double x[], int incx) +void dscal(int n, float sa, float x[], int incx) /******************************************************************************/ /** @@ -1402,9 +1402,9 @@ void dscal(int n, double sa, double x[], int incx) Input, int N, the number of entries in the vector. - Input, double SA, the multiplier. + Input, float SA, the multiplier. - Input/output, double X[*], the vector to be scaled. + Input/output, float X[*], the vector to be scaled. Input, int INCX, the increment between successive entries of X. */ @@ -1441,7 +1441,7 @@ void dscal(int n, double sa, double x[], int incx) /******************************************************************************/ -void dswap(int n, double x[], int incx, double y[], int incy) +void dswap(int n, float x[], int incx, float y[], int incy) /******************************************************************************/ /** @@ -1477,11 +1477,11 @@ void dswap(int n, double x[], int incx, double y[], int incy) Input, int N, the number of entries in the vectors. - Input/output, double X[*], one of the vectors to swap. + Input/output, float X[*], one of the vectors to swap. Input, int INCX, the increment between successive entries of X. - Input/output, double Y[*], one of the vectors to swap. + Input/output, float Y[*], one of the vectors to swap. Input, int INCY, the increment between successive elements of Y. */ @@ -1489,7 +1489,7 @@ void dswap(int n, double x[], int incx, double y[], int incy) if (n <= 0) return; int i, ix, iy, m; - double temp; + float temp; if (incx == 1 && incy == 1) { m = n % 3; @@ -1526,7 +1526,7 @@ void dswap(int n, double x[], int incx, double y[], int incy) /******************************************************************************/ -void qr_solve(double x[], int m, int n, double a[], double b[]) +void qr_solve(float x[], int m, int n, float a[], float b[]) /******************************************************************************/ /** @@ -1569,14 +1569,14 @@ void qr_solve(double x[], int m, int n, double a[], double b[]) Input, int N, the number of columns of A. - Input, double A[M*N], the matrix. + Input, float A[M*N], the matrix. - Input, double B[M], the right hand side. + Input, float B[M], the right hand side. - Output, double QR_SOLVE[N], the least squares solution. + Output, float QR_SOLVE[N], the least squares solution. */ { - double a_qr[n * m], qraux[n], r[m], tol; + float a_qr[n * m], qraux[n], r[m], tol; int ind, itask, jpvt[n], kr, lda; r8mat_copy(a_qr, m, n, a); diff --git a/Marlin/qr_solve.h b/Marlin/qr_solve.h index 3ea30e9e7d..c409220d31 100644 --- a/Marlin/qr_solve.h +++ b/Marlin/qr_solve.h @@ -22,23 +22,23 @@ #include "MarlinConfig.h" -#if ENABLED(AUTO_BED_LEVELING_GRID) +#if ENABLED(AUTO_BED_LEVELING_LINEAR) -void daxpy(int n, double da, double dx[], int incx, double dy[], int incy); -double ddot(int n, double dx[], int incx, double dy[], int incy); -double dnrm2(int n, double x[], int incx); -void dqrank(double a[], int lda, int m, int n, double tol, int* kr, - int jpvt[], double qraux[]); -void dqrdc(double a[], int lda, int n, int p, double qraux[], int jpvt[], - double work[], int job); -int dqrls(double a[], int lda, int m, int n, double tol, int* kr, double b[], - double x[], double rsd[], int jpvt[], double qraux[], int itask); -void dqrlss(double a[], int lda, int m, int n, int kr, double b[], double x[], - double rsd[], int jpvt[], double qraux[]); -int dqrsl(double a[], int lda, int n, int k, double qraux[], double y[], - double qy[], double qty[], double b[], double rsd[], double ab[], int job); -void dscal(int n, double sa, double x[], int incx); -void dswap(int n, double x[], int incx, double y[], int incy); -void qr_solve(double x[], int m, int n, double a[], double b[]); +void daxpy(int n, float da, float dx[], int incx, float dy[], int incy); +float ddot(int n, float dx[], int incx, float dy[], int incy); +float dnrm2(int n, float x[], int incx); +void dqrank(float a[], int lda, int m, int n, float tol, int* kr, + int jpvt[], float qraux[]); +void dqrdc(float a[], int lda, int n, int p, float qraux[], int jpvt[], + float work[], int job); +int dqrls(float a[], int lda, int m, int n, float tol, int* kr, float b[], + float x[], float rsd[], int jpvt[], float qraux[], int itask); +void dqrlss(float a[], int lda, int m, int n, int kr, float b[], float x[], + float rsd[], int jpvt[], float qraux[]); +int dqrsl(float a[], int lda, int n, int k, float qraux[], float y[], + float qy[], float qty[], float b[], float rsd[], float ab[], int job); +void dscal(int n, float sa, float x[], int incx); +void dswap(int n, float x[], int incx, float y[], int incy); +void qr_solve(float x[], int m, int n, float a[], float b[]); #endif diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index 88e8cd5600..82289a5d6c 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -82,30 +82,29 @@ unsigned int Stepper::cleaning_buffer_counter = 0; bool Stepper::locked_z2_motor = false; #endif -long Stepper::counter_X = 0, - Stepper::counter_Y = 0, - Stepper::counter_Z = 0, - Stepper::counter_E = 0; +long Stepper::counter_X = 0, + Stepper::counter_Y = 0, + Stepper::counter_Z = 0, + Stepper::counter_E = 0; -volatile unsigned long Stepper::step_events_completed = 0; // The number of step events executed in the current block +volatile uint32_t Stepper::step_events_completed = 0; // The number of step events executed in the current block #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) - unsigned char Stepper::old_OCR0A; - volatile unsigned char Stepper::eISR_Rate = 200; // Keep the ISR at a low rate until needed + uint8_t Stepper::old_OCR0A = 0; + volatile uint8_t Stepper::eISR_Rate = 200; // Keep the ISR at a low rate until needed #if ENABLED(LIN_ADVANCE) volatile int Stepper::e_steps[E_STEPPERS]; - int Stepper::extruder_advance_k = LIN_ADVANCE_K, - Stepper::final_estep_rate, + int Stepper::final_estep_rate, Stepper::current_estep_rate[E_STEPPERS], Stepper::current_adv_steps[E_STEPPERS]; #else - long Stepper::e_steps[E_STEPPERS], - Stepper::final_advance = 0, - Stepper::old_advance = 0, - Stepper::advance_rate, - Stepper::advance; + long Stepper::e_steps[E_STEPPERS], + Stepper::final_advance = 0, + Stepper::old_advance = 0, + Stepper::advance_rate, + Stepper::advance; #endif #endif @@ -115,14 +114,14 @@ volatile long Stepper::count_position[NUM_AXIS] = { 0 }; volatile signed char Stepper::count_direction[NUM_AXIS] = { 1, 1, 1, 1 }; #if ENABLED(MIXING_EXTRUDER) - long Stepper::counter_M[MIXING_STEPPERS]; + long Stepper::counter_m[MIXING_STEPPERS]; #endif unsigned short Stepper::acc_step_rate; // needed for deceleration start point uint8_t Stepper::step_loops, Stepper::step_loops_nominal; unsigned short Stepper::OCR1A_nominal; -volatile long Stepper::endstops_trigsteps[3]; +volatile long Stepper::endstops_trigsteps[XYZ]; #if ENABLED(X_DUAL_STEPPER_DRIVERS) #define X_APPLY_DIR(v,Q) do{ X_DIR_WRITE(v); X2_DIR_WRITE((v) != INVERT_X2_VS_X_DIR); }while(0) @@ -162,14 +161,14 @@ volatile long Stepper::endstops_trigsteps[3]; #if ENABLED(Z_DUAL_ENDSTOPS) #define Z_APPLY_STEP(v,Q) \ if (performing_homing) { \ - if (Z_HOME_DIR > 0) {\ - if (!(TEST(endstops.old_endstop_bits, Z_MAX) && (count_direction[Z_AXIS] > 0)) && !locked_z_motor) Z_STEP_WRITE(v); \ - if (!(TEST(endstops.old_endstop_bits, Z2_MAX) && (count_direction[Z_AXIS] > 0)) && !locked_z2_motor) Z2_STEP_WRITE(v); \ - } \ - else { \ + if (Z_HOME_DIR < 0) { \ if (!(TEST(endstops.old_endstop_bits, Z_MIN) && (count_direction[Z_AXIS] < 0)) && !locked_z_motor) Z_STEP_WRITE(v); \ if (!(TEST(endstops.old_endstop_bits, Z2_MIN) && (count_direction[Z_AXIS] < 0)) && !locked_z2_motor) Z2_STEP_WRITE(v); \ } \ + else { \ + if (!(TEST(endstops.old_endstop_bits, Z_MAX) && (count_direction[Z_AXIS] > 0)) && !locked_z_motor) Z_STEP_WRITE(v); \ + if (!(TEST(endstops.old_endstop_bits, Z2_MAX) && (count_direction[Z_AXIS] > 0)) && !locked_z2_motor) Z2_STEP_WRITE(v); \ + } \ } \ else { \ Z_STEP_WRITE(v); \ @@ -289,11 +288,17 @@ void Stepper::set_directions() { count_direction[AXIS ##_AXIS] = 1; \ } - SET_STEP_DIR(X); // A - SET_STEP_DIR(Y); // B - SET_STEP_DIR(Z); // C + #if HAS_X_DIR + SET_STEP_DIR(X); // A + #endif + #if HAS_Y_DIR + SET_STEP_DIR(Y); // B + #endif + #if HAS_Z_DIR + SET_STEP_DIR(Z); // C + #endif - #if DISABLED(ADVANCE) + #if DISABLED(ADVANCE) && DISABLED(LIN_ADVANCE) if (motor_direction(E_AXIS)) { REV_E_DIR(); count_direction[E_AXIS] = -1; @@ -302,22 +307,52 @@ void Stepper::set_directions() { NORM_E_DIR(); count_direction[E_AXIS] = 1; } - #endif //!ADVANCE + #endif // !ADVANCE && !LIN_ADVANCE } -// "The Stepper Driver Interrupt" - This timer interrupt is the workhorse. -// It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately. +#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE) + extern volatile uint8_t e_hit; +#endif + +/** + * Stepper Driver Interrupt + * + * Directly pulses the stepper motors at high frequency. + * Timer 1 runs at a base frequency of 2MHz, with this ISR using OCR1A compare mode. + * + * OCR1A Frequency + * 1 2 MHz + * 50 40 KHz + * 100 20 KHz - capped max rate + * 200 10 KHz - nominal max rate + * 2000 1 KHz - sleep rate + * 4000 500 Hz - init rate + */ ISR(TIMER1_COMPA_vect) { Stepper::isr(); } void Stepper::isr() { + //Disable Timer0 ISRs and enable global ISR again to capture UART events (incoming chars) + #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) + CBI(TIMSK0, OCIE0A); //estepper ISR + #endif + CBI(TIMSK0, OCIE0B); //Temperature ISR + DISABLE_STEPPER_DRIVER_INTERRUPT(); + sei(); + if (cleaning_buffer_counter) { + --cleaning_buffer_counter; current_block = NULL; planner.discard_current_block(); #ifdef SD_FINISHED_RELEASECOMMAND - if ((cleaning_buffer_counter == 1) && (SD_FINISHED_STEPPERRELEASE)) enqueue_and_echo_commands_P(PSTR(SD_FINISHED_RELEASECOMMAND)); + if (!cleaning_buffer_counter && (SD_FINISHED_STEPPERRELEASE)) enqueue_and_echo_commands_P(PSTR(SD_FINISHED_RELEASECOMMAND)); #endif - cleaning_buffer_counter--; - OCR1A = 200; + OCR1A = 200; // Run at max speed - 10 KHz + //re-enable ISRs + #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) + SBI(TIMSK0, OCIE0A); + #endif + SBI(TIMSK0, OCIE0B); + ENABLE_STEPPER_DRIVER_INTERRUPT(); return; } @@ -326,7 +361,6 @@ void Stepper::isr() { // Anything in the buffer? current_block = planner.get_current_block(); if (current_block) { - current_block->busy = true; trapezoid_generator_reset(); // Initialize Bresenham counters to 1/2 the ceiling @@ -334,15 +368,25 @@ void Stepper::isr() { #if ENABLED(MIXING_EXTRUDER) MIXING_STEPPERS_LOOP(i) - counter_M[i] = -(current_block->mix_event_count[i] >> 1); + counter_m[i] = -(current_block->mix_event_count[i] >> 1); #endif step_events_completed = 0; + #if ENABLED(ENDSTOP_INTERRUPTS_FEATURE) + e_hit = 2; // Needed for the case an endstop is already triggered before the new move begins. + // No 'change' can be detected. + #endif + #if ENABLED(Z_LATE_ENABLE) if (current_block->steps[Z_AXIS] > 0) { enable_z(); - OCR1A = 2000; //1ms wait + OCR1A = 2000; // Run at slow speed - 1 KHz + #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) + SBI(TIMSK0, OCIE0A); + #endif + SBI(TIMSK0, OCIE0B); + ENABLE_STEPPER_DRIVER_INTERRUPT(); return; } #endif @@ -352,288 +396,329 @@ void Stepper::isr() { // #endif } else { - OCR1A = 2000; // 1kHz. + OCR1A = 2000; // Run at slow speed - 1 KHz + #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) + SBI(TIMSK0, OCIE0A); + #endif + SBI(TIMSK0, OCIE0B); + ENABLE_STEPPER_DRIVER_INTERRUPT(); + return; } } - if (current_block) { + // Update endstops state, if enabled + if ((endstops.enabled + #if HAS_BED_PROBE + || endstops.z_probe_enabled + #endif + ) + #if ENABLED(ENDSTOP_INTERRUPTS_FEATURE) + && e_hit + #endif + ) { + endstops.update(); - // Update endstops state, if enabled - if (endstops.enabled - #if HAS_BED_PROBE - || endstops.z_probe_enabled - #endif - ) endstops.update(); + #if ENABLED(ENDSTOP_INTERRUPTS_FEATURE) + e_hit--; + #endif + } - // Take multiple steps per interrupt (For high speed moves) - for (int8_t i = 0; i < step_loops; i++) { - #ifndef USBCON - customizedSerial.checkRx(); // Check for serial chars. + // Take multiple steps per interrupt (For high speed moves) + bool all_steps_done = false; + for (int8_t i = 0; i < step_loops; i++) { + #if ENABLED(LIN_ADVANCE) + + counter_E += current_block->steps[E_AXIS]; + if (counter_E > 0) { + counter_E -= current_block->step_event_count; + #if DISABLED(MIXING_EXTRUDER) + // Don't step E here for mixing extruder + count_position[E_AXIS] += count_direction[E_AXIS]; + motor_direction(E_AXIS) ? --e_steps[TOOL_E_INDEX] : ++e_steps[TOOL_E_INDEX]; + #endif + } + + #if ENABLED(MIXING_EXTRUDER) + // Step mixing steppers proportionally + const bool dir = motor_direction(E_AXIS); + MIXING_STEPPERS_LOOP(j) { + counter_m[j] += current_block->steps[E_AXIS]; + if (counter_m[j] > 0) { + counter_m[j] -= current_block->mix_event_count[j]; + dir ? --e_steps[j] : ++e_steps[j]; + } + } #endif - #if ENABLED(LIN_ADVANCE) + #elif ENABLED(ADVANCE) - counter_E += current_block->steps[E_AXIS]; - if (counter_E > 0) { - counter_E -= current_block->step_event_count; - #if DISABLED(MIXING_EXTRUDER) - // Don't step E here for mixing extruder - count_position[E_AXIS] += count_direction[E_AXIS]; - e_steps[TOOL_E_INDEX] += motor_direction(E_AXIS) ? -1 : 1; - #endif - } - - #if ENABLED(MIXING_EXTRUDER) - // Step mixing steppers proportionally - long dir = motor_direction(E_AXIS) ? -1 : 1; - MIXING_STEPPERS_LOOP(j) { - counter_m[j] += current_block->steps[E_AXIS]; - if (counter_m[j] > 0) { - counter_m[j] -= current_block->mix_event_count[j]; - e_steps[j] += dir; - } - } + // Always count the unified E axis + counter_E += current_block->steps[E_AXIS]; + if (counter_E > 0) { + counter_E -= current_block->step_event_count; + #if DISABLED(MIXING_EXTRUDER) + // Don't step E here for mixing extruder + motor_direction(E_AXIS) ? --e_steps[TOOL_E_INDEX] : ++e_steps[TOOL_E_INDEX]; #endif + } - if (current_block->use_advance_lead) { - int delta_adv_steps = (((long)extruder_advance_k * current_estep_rate[TOOL_E_INDEX]) >> 9) - current_adv_steps[TOOL_E_INDEX]; - #if ENABLED(MIXING_EXTRUDER) - // Mixing extruders apply advance lead proportionally - MIXING_STEPPERS_LOOP(j) { - int steps = delta_adv_steps * current_block->step_event_count / current_block->mix_event_count[j]; - e_steps[j] += steps; - current_adv_steps[j] += steps; - } - #else - // For most extruders, advance the single E stepper - e_steps[TOOL_E_INDEX] += delta_adv_steps; - current_adv_steps[TOOL_E_INDEX] += delta_adv_steps; - #endif + #if ENABLED(MIXING_EXTRUDER) + + // Step mixing steppers proportionally + const bool dir = motor_direction(E_AXIS); + MIXING_STEPPERS_LOOP(j) { + counter_m[j] += current_block->steps[E_AXIS]; + if (counter_m[j] > 0) { + counter_m[j] -= current_block->mix_event_count[j]; + dir ? --e_steps[j] : ++e_steps[j]; + } } - #elif ENABLED(ADVANCE) + #endif // MIXING_EXTRUDER - // Always count the unified E axis - counter_E += current_block->steps[E_AXIS]; - if (counter_E > 0) { - counter_E -= current_block->step_event_count; - #if DISABLED(MIXING_EXTRUDER) - // Don't step E here for mixing extruder - e_steps[TOOL_E_INDEX] += motor_direction(E_AXIS) ? -1 : 1; - #endif - } + #endif // ADVANCE or LIN_ADVANCE - #if ENABLED(MIXING_EXTRUDER) + #define _COUNTER(AXIS) counter_## AXIS + #define _APPLY_STEP(AXIS) AXIS ##_APPLY_STEP + #define _INVERT_STEP_PIN(AXIS) INVERT_## AXIS ##_STEP_PIN - // Step mixing steppers proportionally - long dir = motor_direction(E_AXIS) ? -1 : 1; - MIXING_STEPPERS_LOOP(j) { - counter_m[j] += current_block->steps[E_AXIS]; - if (counter_m[j] > 0) { - counter_m[j] -= current_block->mix_event_count[j]; - e_steps[j] += dir; - } - } + // Advance the Bresenham counter; start a pulse if the axis needs a step + #define PULSE_START(AXIS) \ + _COUNTER(AXIS) += current_block->steps[_AXIS(AXIS)]; \ + if (_COUNTER(AXIS) > 0) { _APPLY_STEP(AXIS)(!_INVERT_STEP_PIN(AXIS),0); } - #endif // MIXING_EXTRUDER + // Stop an active pulse, reset the Bresenham counter, update the position + #define PULSE_STOP(AXIS) \ + if (_COUNTER(AXIS) > 0) { \ + _COUNTER(AXIS) -= current_block->step_event_count; \ + count_position[_AXIS(AXIS)] += count_direction[_AXIS(AXIS)]; \ + _APPLY_STEP(AXIS)(_INVERT_STEP_PIN(AXIS),0); \ + } - #endif // ADVANCE or LIN_ADVANCE + #define CYCLES_EATEN_BY_CODE 240 - #define _COUNTER(AXIS) counter_## AXIS - #define _APPLY_STEP(AXIS) AXIS ##_APPLY_STEP - #define _INVERT_STEP_PIN(AXIS) INVERT_## AXIS ##_STEP_PIN - - #define STEP_ADD(AXIS) \ - _COUNTER(AXIS) += current_block->steps[_AXIS(AXIS)]; \ - if (_COUNTER(AXIS) > 0) { _APPLY_STEP(AXIS)(!_INVERT_STEP_PIN(AXIS),0); } - - STEP_ADD(X); - STEP_ADD(Y); - STEP_ADD(Z); - - #if DISABLED(ADVANCE) && DISABLED(LIN_ADVANCE) - #if ENABLED(MIXING_EXTRUDER) - // Keep updating the single E axis - counter_E += current_block->steps[E_AXIS]; - // Tick the counters used for this mix - MIXING_STEPPERS_LOOP(j) { - // Step mixing steppers (proportionally) - counter_M[j] += current_block->steps[E_AXIS]; - // Step when the counter goes over zero - if (counter_M[j] > 0) En_STEP_WRITE(j, !INVERT_E_STEP_PIN); - } - #else // !MIXING_EXTRUDER - STEP_ADD(E); - #endif - #endif // !ADVANCE && !LIN_ADVANCE - - #define STEP_IF_COUNTER(AXIS) \ - if (_COUNTER(AXIS) > 0) { \ - _COUNTER(AXIS) -= current_block->step_event_count; \ - count_position[_AXIS(AXIS)] += count_direction[_AXIS(AXIS)]; \ - _APPLY_STEP(AXIS)(_INVERT_STEP_PIN(AXIS),0); \ - } - - STEP_IF_COUNTER(X); - STEP_IF_COUNTER(Y); - STEP_IF_COUNTER(Z); - - #if DISABLED(ADVANCE) && DISABLED(LIN_ADVANCE) - #if ENABLED(MIXING_EXTRUDER) - // Always step the single E axis - if (counter_E > 0) { - counter_E -= current_block->step_event_count; - count_position[E_AXIS] += count_direction[E_AXIS]; - } - MIXING_STEPPERS_LOOP(j) { - if (counter_M[j] > 0) { - counter_M[j] -= current_block->mix_event_count[j]; - En_STEP_WRITE(j, INVERT_E_STEP_PIN); - } - } - #else // !MIXING_EXTRUDER - STEP_IF_COUNTER(E); - #endif - #endif // !ADVANCE && !LIN_ADVANCE - - step_events_completed++; - if (step_events_completed >= current_block->step_event_count) break; - } - - #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) - // If we have esteps to execute, fire the next ISR "now" - if (e_steps[TOOL_E_INDEX]) OCR0A = TCNT0 + 2; + // If a minimum pulse time was specified get the CPU clock + #if STEP_PULSE_CYCLES > CYCLES_EATEN_BY_CODE + static uint32_t pulse_start; + pulse_start = TCNT0; #endif - // Calculate new timer value - unsigned short timer, step_rate; - if (step_events_completed <= (unsigned long)current_block->accelerate_until) { + #if HAS_X_STEP + PULSE_START(X); + #endif + #if HAS_Y_STEP + PULSE_START(Y); + #endif + #if HAS_Z_STEP + PULSE_START(Z); + #endif - MultiU24X32toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate); - acc_step_rate += current_block->initial_rate; - - // upper limit - NOMORE(acc_step_rate, current_block->nominal_rate); - - // step_rate to timer interval - timer = calc_timer(acc_step_rate); - OCR1A = timer; - acceleration_time += timer; - - #if ENABLED(LIN_ADVANCE) - - if (current_block->use_advance_lead) - current_estep_rate[TOOL_E_INDEX] = ((unsigned long)acc_step_rate * current_block->e_speed_multiplier8) >> 8; - - if (current_block->use_advance_lead) { - #if ENABLED(MIXING_EXTRUDER) - MIXING_STEPPERS_LOOP(j) - current_estep_rate[j] = ((unsigned long)acc_step_rate * current_block->e_speed_multiplier8 * current_block->step_event_count / current_block->mix_event_count[j]) >> 8; - #else - current_estep_rate[TOOL_E_INDEX] = ((unsigned long)acc_step_rate * current_block->e_speed_multiplier8) >> 8; - #endif + // For non-advance use linear interpolation for E also + #if DISABLED(ADVANCE) && DISABLED(LIN_ADVANCE) + #if ENABLED(MIXING_EXTRUDER) + // Keep updating the single E axis + counter_E += current_block->steps[E_AXIS]; + // Tick the counters used for this mix + MIXING_STEPPERS_LOOP(j) { + // Step mixing steppers (proportionally) + counter_m[j] += current_block->steps[E_AXIS]; + // Step when the counter goes over zero + if (counter_m[j] > 0) En_STEP_WRITE(j, !INVERT_E_STEP_PIN); } - - #elif ENABLED(ADVANCE) - - advance += advance_rate * step_loops; - //NOLESS(advance, current_block->advance); - - long advance_whole = advance >> 8, - advance_factor = advance_whole - old_advance; - - // Do E steps + advance steps - #if ENABLED(MIXING_EXTRUDER) - // ...for mixing steppers proportionally - MIXING_STEPPERS_LOOP(j) - e_steps[j] += advance_factor * current_block->step_event_count / current_block->mix_event_count[j]; - #else - // ...for the active extruder - e_steps[TOOL_E_INDEX] += advance_factor; - #endif - - old_advance = advance_whole; - - #endif // ADVANCE or LIN_ADVANCE - - #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) - eISR_Rate = (timer >> 2) * step_loops / abs(e_steps[TOOL_E_INDEX]); + #else // !MIXING_EXTRUDER + PULSE_START(E); #endif - } - else if (step_events_completed > (unsigned long)current_block->decelerate_after) { - MultiU24X32toH16(step_rate, deceleration_time, current_block->acceleration_rate); + #endif // !ADVANCE && !LIN_ADVANCE - if (step_rate <= acc_step_rate) { // Still decelerating? - step_rate = acc_step_rate - step_rate; - NOLESS(step_rate, current_block->final_rate); - } - else - step_rate = current_block->final_rate; + // For a minimum pulse time wait before stopping pulses + #if STEP_PULSE_CYCLES > CYCLES_EATEN_BY_CODE + while ((uint32_t)(TCNT0 - pulse_start) < STEP_PULSE_CYCLES - CYCLES_EATEN_BY_CODE) { /* nada */ } + #endif - // step_rate to timer interval - timer = calc_timer(step_rate); - OCR1A = timer; - deceleration_time += timer; + #if HAS_X_STEP + PULSE_STOP(X); + #endif + #if HAS_Y_STEP + PULSE_STOP(Y); + #endif + #if HAS_Z_STEP + PULSE_STOP(Z); + #endif - #if ENABLED(LIN_ADVANCE) - - if (current_block->use_advance_lead) { - #if ENABLED(MIXING_EXTRUDER) - MIXING_STEPPERS_LOOP(j) - current_estep_rate[j] = ((unsigned long)step_rate * current_block->e_speed_multiplier8 * current_block->step_event_count / current_block->mix_event_count[j]) >> 8; - #else - current_estep_rate[TOOL_E_INDEX] = ((unsigned long)step_rate * current_block->e_speed_multiplier8) >> 8; - #endif + #if DISABLED(ADVANCE) && DISABLED(LIN_ADVANCE) + #if ENABLED(MIXING_EXTRUDER) + // Always step the single E axis + if (counter_E > 0) { + counter_E -= current_block->step_event_count; + count_position[E_AXIS] += count_direction[E_AXIS]; } - - #elif ENABLED(ADVANCE) - - advance -= advance_rate * step_loops; - NOLESS(advance, final_advance); - - // Do E steps + advance steps - long advance_whole = advance >> 8, - advance_factor = advance_whole - old_advance; - - #if ENABLED(MIXING_EXTRUDER) - MIXING_STEPPERS_LOOP(j) - e_steps[j] += advance_factor * current_block->step_event_count / current_block->mix_event_count[j]; - #else - e_steps[TOOL_E_INDEX] += advance_factor; - #endif - - old_advance = advance_whole; - - #endif // ADVANCE or LIN_ADVANCE - - #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) - eISR_Rate = (timer >> 2) * step_loops / abs(e_steps[TOOL_E_INDEX]); + MIXING_STEPPERS_LOOP(j) { + if (counter_m[j] > 0) { + counter_m[j] -= current_block->mix_event_count[j]; + En_STEP_WRITE(j, INVERT_E_STEP_PIN); + } + } + #else // !MIXING_EXTRUDER + PULSE_STOP(E); #endif - } - else { + #endif // !ADVANCE && !LIN_ADVANCE - #if ENABLED(LIN_ADVANCE) - - if (current_block->use_advance_lead) - current_estep_rate[TOOL_E_INDEX] = final_estep_rate; - - eISR_Rate = (OCR1A_nominal >> 2) * step_loops_nominal / abs(e_steps[TOOL_E_INDEX]); - - #endif - - OCR1A = OCR1A_nominal; - // ensure we're running at the correct step rate, even if we just came off an acceleration - step_loops = step_loops_nominal; - } - - OCR1A = (OCR1A < (TCNT1 + 16)) ? (TCNT1 + 16) : OCR1A; - - // If current block is finished, reset pointer - if (step_events_completed >= current_block->step_event_count) { - current_block = NULL; - planner.discard_current_block(); + if (++step_events_completed >= current_block->step_event_count) { + all_steps_done = true; + break; } } + + #if ENABLED(LIN_ADVANCE) + if (current_block->use_advance_lead) { + int delta_adv_steps = current_estep_rate[TOOL_E_INDEX] - current_adv_steps[TOOL_E_INDEX]; + current_adv_steps[TOOL_E_INDEX] += delta_adv_steps; + #if ENABLED(MIXING_EXTRUDER) + // Mixing extruders apply advance lead proportionally + MIXING_STEPPERS_LOOP(j) + e_steps[j] += delta_adv_steps * current_block->step_event_count / current_block->mix_event_count[j]; + #else + // For most extruders, advance the single E stepper + e_steps[TOOL_E_INDEX] += delta_adv_steps; + #endif + } + #endif + + #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) + // If we have esteps to execute, fire the next advance_isr "now" + if (e_steps[TOOL_E_INDEX]) OCR0A = TCNT0 + 2; + #endif + + // Calculate new timer value + if (step_events_completed <= (uint32_t)current_block->accelerate_until) { + + MultiU24X32toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate); + acc_step_rate += current_block->initial_rate; + + // upper limit + NOMORE(acc_step_rate, current_block->nominal_rate); + + // step_rate to timer interval + uint16_t timer = calc_timer(acc_step_rate); + OCR1A = timer; + acceleration_time += timer; + + #if ENABLED(LIN_ADVANCE) + + if (current_block->use_advance_lead) { + #if ENABLED(MIXING_EXTRUDER) + MIXING_STEPPERS_LOOP(j) + current_estep_rate[j] = ((uint32_t)acc_step_rate * current_block->abs_adv_steps_multiplier8 * current_block->step_event_count / current_block->mix_event_count[j]) >> 17; + #else + current_estep_rate[TOOL_E_INDEX] = ((uint32_t)acc_step_rate * current_block->abs_adv_steps_multiplier8) >> 17; + #endif + } + + #elif ENABLED(ADVANCE) + + advance += advance_rate * step_loops; + //NOLESS(advance, current_block->advance); + + long advance_whole = advance >> 8, + advance_factor = advance_whole - old_advance; + + // Do E steps + advance steps + #if ENABLED(MIXING_EXTRUDER) + // ...for mixing steppers proportionally + MIXING_STEPPERS_LOOP(j) + e_steps[j] += advance_factor * current_block->step_event_count / current_block->mix_event_count[j]; + #else + // ...for the active extruder + e_steps[TOOL_E_INDEX] += advance_factor; + #endif + + old_advance = advance_whole; + + #endif // ADVANCE or LIN_ADVANCE + + #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) + eISR_Rate = (timer >> 3) * step_loops / abs(e_steps[TOOL_E_INDEX]); //>> 3 is divide by 8. Reason: Timer 1 runs at 16/8=2MHz, Timer 0 at 16/64=0.25MHz. ==> 2/0.25=8. + #endif + } + else if (step_events_completed > (uint32_t)current_block->decelerate_after) { + uint16_t step_rate; + MultiU24X32toH16(step_rate, deceleration_time, current_block->acceleration_rate); + + if (step_rate < acc_step_rate) { // Still decelerating? + step_rate = acc_step_rate - step_rate; + NOLESS(step_rate, current_block->final_rate); + } + else + step_rate = current_block->final_rate; + + // step_rate to timer interval + uint16_t timer = calc_timer(step_rate); + OCR1A = timer; + deceleration_time += timer; + + #if ENABLED(LIN_ADVANCE) + + if (current_block->use_advance_lead) { + #if ENABLED(MIXING_EXTRUDER) + MIXING_STEPPERS_LOOP(j) + current_estep_rate[j] = ((uint32_t)step_rate * current_block->abs_adv_steps_multiplier8 * current_block->step_event_count / current_block->mix_event_count[j]) >> 17; + #else + current_estep_rate[TOOL_E_INDEX] = ((uint32_t)step_rate * current_block->abs_adv_steps_multiplier8) >> 17; + #endif + } + + #elif ENABLED(ADVANCE) + + advance -= advance_rate * step_loops; + NOLESS(advance, final_advance); + + // Do E steps + advance steps + long advance_whole = advance >> 8, + advance_factor = advance_whole - old_advance; + + #if ENABLED(MIXING_EXTRUDER) + MIXING_STEPPERS_LOOP(j) + e_steps[j] += advance_factor * current_block->step_event_count / current_block->mix_event_count[j]; + #else + e_steps[TOOL_E_INDEX] += advance_factor; + #endif + + old_advance = advance_whole; + + #endif // ADVANCE or LIN_ADVANCE + + #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) + eISR_Rate = (timer >> 3) * step_loops / abs(e_steps[TOOL_E_INDEX]); + #endif + } + else { + + #if ENABLED(LIN_ADVANCE) + + if (current_block->use_advance_lead) + current_estep_rate[TOOL_E_INDEX] = final_estep_rate; + + eISR_Rate = (OCR1A_nominal >> 3) * step_loops_nominal / abs(e_steps[TOOL_E_INDEX]); + + #endif + + OCR1A = OCR1A_nominal; + // ensure we're running at the correct step rate, even if we just came off an acceleration + step_loops = step_loops_nominal; + } + + NOLESS(OCR1A, TCNT1 + 16); + + // If current block is finished, reset pointer + if (all_steps_done) { + current_block = NULL; + planner.discard_current_block(); + } + #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) + SBI(TIMSK0, OCIE0A); + #endif + SBI(TIMSK0, OCIE0B); + ENABLE_STEPPER_DRIVER_INTERRUPT(); } #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) @@ -647,29 +732,62 @@ void Stepper::isr() { old_OCR0A += eISR_Rate; OCR0A = old_OCR0A; - #define STEP_E_ONCE(INDEX) \ - if (e_steps[INDEX] != 0) { \ + #define SET_E_STEP_DIR(INDEX) \ + if (e_steps[INDEX]) E## INDEX ##_DIR_WRITE(e_steps[INDEX] < 0 ? INVERT_E## INDEX ##_DIR : !INVERT_E## INDEX ##_DIR) + + #define START_E_PULSE(INDEX) \ + if (e_steps[INDEX]) E## INDEX ##_STEP_WRITE(!INVERT_E_STEP_PIN) + + #define STOP_E_PULSE(INDEX) \ + if (e_steps[INDEX]) { \ + e_steps[INDEX] < 0 ? ++e_steps[INDEX] : --e_steps[INDEX]; \ E## INDEX ##_STEP_WRITE(INVERT_E_STEP_PIN); \ - if (e_steps[INDEX] < 0) { \ - E## INDEX ##_DIR_WRITE(INVERT_E## INDEX ##_DIR); \ - e_steps[INDEX]++; \ - } \ - else { \ - E## INDEX ##_DIR_WRITE(!INVERT_E## INDEX ##_DIR); \ - e_steps[INDEX]--; \ - } \ - E## INDEX ##_STEP_WRITE(!INVERT_E_STEP_PIN); \ } + SET_E_STEP_DIR(0); + #if E_STEPPERS > 1 + SET_E_STEP_DIR(1); + #if E_STEPPERS > 2 + SET_E_STEP_DIR(2); + #if E_STEPPERS > 3 + SET_E_STEP_DIR(3); + #endif + #endif + #endif + + #define CYCLES_EATEN_BY_E 60 + // Step all E steppers that have steps for (uint8_t i = 0; i < step_loops; i++) { - STEP_E_ONCE(0); + + #if STEP_PULSE_CYCLES > CYCLES_EATEN_BY_E + static uint32_t pulse_start; + pulse_start = TCNT0; + #endif + + START_E_PULSE(0); #if E_STEPPERS > 1 - STEP_E_ONCE(1); + START_E_PULSE(1); #if E_STEPPERS > 2 - STEP_E_ONCE(2); + START_E_PULSE(2); #if E_STEPPERS > 3 - STEP_E_ONCE(3); + START_E_PULSE(3); + #endif + #endif + #endif + + // For a minimum pulse time wait before stopping pulses + #if STEP_PULSE_CYCLES > CYCLES_EATEN_BY_E + while ((uint32_t)(TCNT0 - pulse_start) < STEP_PULSE_CYCLES - CYCLES_EATEN_BY_E) { /* nada */ } + #endif + + STOP_E_PULSE(0); + #if E_STEPPERS > 1 + STOP_E_PULSE(1); + #if E_STEPPERS > 2 + STOP_E_PULSE(2); + #if E_STEPPERS > 3 + STOP_E_PULSE(3); #endif #endif #endif @@ -681,19 +799,32 @@ void Stepper::isr() { void Stepper::init() { - digipot_init(); //Initialize Digipot Motor Current - microstep_init(); //Initialize Microstepping Pins + // Init Digipot Motor Current + #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM + digipot_init(); + #endif - // initialise TMC Steppers + // Init Microstepping Pins + #if HAS_MICROSTEPS + microstep_init(); + #endif + + // Init TMC Steppers #if ENABLED(HAVE_TMCDRIVER) tmc_init(); #endif - // initialise L6470 Steppers + + // Init TMC2130 Steppers + #if ENABLED(HAVE_TMC2130DRIVER) + tmc2130_init(); + #endif + + // Init L6470 Steppers #if ENABLED(HAVE_L6470DRIVER) L6470_init(); #endif - // Initialize Dir Pins + // Init Dir Pins #if HAS_X_DIR X_DIR_INIT; #endif @@ -725,8 +856,7 @@ void Stepper::init() { E3_DIR_INIT; #endif - //Initialize Enable Pins - steppers default to disabled. - + // Init Enable Pins - steppers default to disabled. #if HAS_X_ENABLE X_ENABLE_INIT; if (!X_ENABLE_ON) X_ENABLE_WRITE(HIGH); @@ -735,7 +865,6 @@ void Stepper::init() { if (!X_ENABLE_ON) X2_ENABLE_WRITE(HIGH); #endif #endif - #if HAS_Y_ENABLE Y_ENABLE_INIT; if (!Y_ENABLE_ON) Y_ENABLE_WRITE(HIGH); @@ -744,7 +873,6 @@ void Stepper::init() { if (!Y_ENABLE_ON) Y2_ENABLE_WRITE(HIGH); #endif #endif - #if HAS_Z_ENABLE Z_ENABLE_INIT; if (!Z_ENABLE_ON) Z_ENABLE_WRITE(HIGH); @@ -753,7 +881,6 @@ void Stepper::init() { if (!Z_ENABLE_ON) Z2_ENABLE_WRITE(HIGH); #endif #endif - #if HAS_E0_ENABLE E0_ENABLE_INIT; if (!E_ENABLE_ON) E0_ENABLE_WRITE(HIGH); @@ -771,9 +898,7 @@ void Stepper::init() { if (!E_ENABLE_ON) E3_ENABLE_WRITE(HIGH); #endif - // - // Init endstops and pullups here - // + // Init endstops and pullups endstops.init(); #define _STEP_INIT(AXIS) AXIS ##_STEP_INIT @@ -787,7 +912,7 @@ void Stepper::init() { #define E_AXIS_INIT(NUM) AXIS_INIT(e## NUM, E## NUM, E) - // Initialize Step Pins + // Init Step Pins #if HAS_X_STEP #if ENABLED(X_DUAL_STEPPER_DRIVERS) || ENABLED(DUAL_X_CARRIAGE) X2_STEP_INIT; @@ -834,6 +959,7 @@ void Stepper::init() { // output mode = 00 (disconnected) TCCR1A &= ~(3 << COM1A0); TCCR1A &= ~(3 << COM1B0); + // Set the timer pre-scaler // Generally we use a divider of 8, resulting in a 2MHz timer // frequency on a 16MHz MCU. If you are going to change this, be @@ -841,6 +967,7 @@ void Stepper::init() { // create_speed_lookuptable.py TCCR1B = (TCCR1B & ~(0x07 << CS10)) | (2 << CS10); + // Init Stepper ISR to 122 Hz for quick starting OCR1A = 0x4000; TCNT1 = 0; ENABLE_STEPPER_DRIVER_INTERRUPT(); @@ -883,37 +1010,46 @@ void Stepper::synchronize() { while (planner.blocks_queued()) idle(); } * This allows get_axis_position_mm to correctly * derive the current XYZ position later on. */ -void Stepper::set_position(const long& x, const long& y, const long& z, const long& e) { +void Stepper::set_position(const long &a, const long &b, const long &c, const long &e) { + + synchronize(); // Bad to set stepper counts in the middle of a move + CRITICAL_SECTION_START; - #if ENABLED(COREXY) + #if CORE_IS_XY // corexy positioning // these equations follow the form of the dA and dB equations on http://www.corexy.com/theory.html - count_position[A_AXIS] = x + y; - count_position[B_AXIS] = x - y; - count_position[Z_AXIS] = z; - #elif ENABLED(COREXZ) + count_position[A_AXIS] = a + b; + count_position[B_AXIS] = CORESIGN(a - b); + count_position[Z_AXIS] = c; + #elif CORE_IS_XZ // corexz planning - count_position[A_AXIS] = x + z; - count_position[Y_AXIS] = y; - count_position[C_AXIS] = x - z; - #elif ENABLED(COREYZ) + count_position[A_AXIS] = a + c; + count_position[Y_AXIS] = b; + count_position[C_AXIS] = CORESIGN(a - c); + #elif CORE_IS_YZ // coreyz planning - count_position[X_AXIS] = x; - count_position[B_AXIS] = y + z; - count_position[C_AXIS] = y - z; + count_position[X_AXIS] = a; + count_position[B_AXIS] = b + c; + count_position[C_AXIS] = CORESIGN(b - c); #else // default non-h-bot planning - count_position[X_AXIS] = x; - count_position[Y_AXIS] = y; - count_position[Z_AXIS] = z; + count_position[X_AXIS] = a; + count_position[Y_AXIS] = b; + count_position[Z_AXIS] = c; #endif count_position[E_AXIS] = e; CRITICAL_SECTION_END; } -void Stepper::set_e_position(const long& e) { +void Stepper::set_position(const AxisEnum &axis, const long &v) { + CRITICAL_SECTION_START; + count_position[axis] = v; + CRITICAL_SECTION_END; +} + +void Stepper::set_e_position(const long &e) { CRITICAL_SECTION_START; count_position[E_AXIS] = e; CRITICAL_SECTION_END; @@ -935,16 +1071,17 @@ long Stepper::position(AxisEnum axis) { */ float Stepper::get_axis_position_mm(AxisEnum axis) { float axis_steps; - #if ENABLED(COREXY) || ENABLED(COREXZ) || ENABLED(COREYZ) + #if IS_CORE // Requesting one of the "core" axes? if (axis == CORE_AXIS_1 || axis == CORE_AXIS_2) { CRITICAL_SECTION_START; - long pos1 = count_position[CORE_AXIS_1], - pos2 = count_position[CORE_AXIS_2]; - CRITICAL_SECTION_END; // ((a1+a2)+(a1-a2))/2 -> (a1+a2+a1-a2)/2 -> (a1+a1)/2 -> a1 // ((a1+a2)-(a1-a2))/2 -> (a1+a2-a1+a2)/2 -> (a2+a2)/2 -> a2 - axis_steps = (pos1 + ((axis == CORE_AXIS_1) ? pos2 : -pos2)) * 0.5f; + axis_steps = 0.5f * ( + axis == CORE_AXIS_2 ? CORESIGN(count_position[CORE_AXIS_1] - count_position[CORE_AXIS_2]) + : count_position[CORE_AXIS_1] + count_position[CORE_AXIS_2] + ); + CRITICAL_SECTION_END; } else axis_steps = position(axis); @@ -961,6 +1098,9 @@ void Stepper::finish_and_disable() { void Stepper::quick_stop() { cleaning_buffer_counter = 5000; + #if ENABLED(ENSURE_SMOOTH_MOVES) + planner.clear_block_buffer_runtime(); + #endif DISABLE_STEPPER_DRIVER_INTERRUPT(); while (planner.blocks_queued()) planner.discard_current_block(); current_block = NULL; @@ -969,14 +1109,12 @@ void Stepper::quick_stop() { void Stepper::endstop_triggered(AxisEnum axis) { - #if ENABLED(COREXY) || ENABLED(COREXZ) || ENABLED(COREYZ) + #if IS_CORE - float axis_pos = count_position[axis]; - if (axis == CORE_AXIS_1) - axis_pos = (axis_pos + count_position[CORE_AXIS_2]) * 0.5; - else if (axis == CORE_AXIS_2) - axis_pos = (count_position[CORE_AXIS_1] - axis_pos) * 0.5; - endstops_trigsteps[axis] = axis_pos; + endstops_trigsteps[axis] = 0.5f * ( + axis == CORE_AXIS_2 ? CORESIGN(count_position[CORE_AXIS_1] - count_position[CORE_AXIS_2]) + : count_position[CORE_AXIS_1] + count_position[CORE_AXIS_2] + ); #else // !COREXY && !COREXZ && !COREYZ @@ -994,21 +1132,21 @@ void Stepper::report_positions() { zpos = count_position[Z_AXIS]; CRITICAL_SECTION_END; - #if ENABLED(COREXY) || ENABLED(COREXZ) + #if CORE_IS_XY || CORE_IS_XZ || IS_SCARA SERIAL_PROTOCOLPGM(MSG_COUNT_A); #else SERIAL_PROTOCOLPGM(MSG_COUNT_X); #endif SERIAL_PROTOCOL(xpos); - #if ENABLED(COREXY) || ENABLED(COREYZ) + #if CORE_IS_XY || CORE_IS_YZ || IS_SCARA SERIAL_PROTOCOLPGM(" B:"); #else SERIAL_PROTOCOLPGM(" Y:"); #endif SERIAL_PROTOCOL(ypos); - #if ENABLED(COREXZ) || ENABLED(COREYZ) + #if CORE_IS_XZ || CORE_IS_YZ SERIAL_PROTOCOLPGM(" C:"); #else SERIAL_PROTOCOLPGM(" Z:"); @@ -1020,24 +1158,24 @@ void Stepper::report_positions() { #if ENABLED(BABYSTEPPING) + #define _ENABLE(axis) enable_## axis() + #define _READ_DIR(AXIS) AXIS ##_DIR_READ + #define _INVERT_DIR(AXIS) INVERT_## AXIS ##_DIR + #define _APPLY_DIR(AXIS, INVERT) AXIS ##_APPLY_DIR(INVERT, true) + + #define BABYSTEP_AXIS(axis, AXIS, INVERT) { \ + _ENABLE(axis); \ + uint8_t old_pin = _READ_DIR(AXIS); \ + _APPLY_DIR(AXIS, _INVERT_DIR(AXIS)^direction^INVERT); \ + _APPLY_STEP(AXIS)(!_INVERT_STEP_PIN(AXIS), true); \ + delayMicroseconds(2); \ + _APPLY_STEP(AXIS)(_INVERT_STEP_PIN(AXIS), true); \ + _APPLY_DIR(AXIS, old_pin); \ + } + // MUST ONLY BE CALLED BY AN ISR, // No other ISR should ever interrupt this! - void Stepper::babystep(const uint8_t axis, const bool direction) { - - #define _ENABLE(axis) enable_## axis() - #define _READ_DIR(AXIS) AXIS ##_DIR_READ - #define _INVERT_DIR(AXIS) INVERT_## AXIS ##_DIR - #define _APPLY_DIR(AXIS, INVERT) AXIS ##_APPLY_DIR(INVERT, true) - - #define BABYSTEP_AXIS(axis, AXIS, INVERT) { \ - _ENABLE(axis); \ - uint8_t old_pin = _READ_DIR(AXIS); \ - _APPLY_DIR(AXIS, _INVERT_DIR(AXIS)^direction^INVERT); \ - _APPLY_STEP(AXIS)(!_INVERT_STEP_PIN(AXIS), true); \ - delayMicroseconds(2); \ - _APPLY_STEP(AXIS)(_INVERT_STEP_PIN(AXIS), true); \ - _APPLY_DIR(AXIS, old_pin); \ - } + void Stepper::babystep(const AxisEnum axis, const bool direction) { switch (axis) { @@ -1100,151 +1238,164 @@ void Stepper::report_positions() { // From Arduino DigitalPotControl example void Stepper::digitalPotWrite(int address, int value) { - digitalWrite(DIGIPOTSS_PIN, LOW); // take the SS pin low to select the chip + WRITE(DIGIPOTSS_PIN, LOW); // take the SS pin low to select the chip SPI.transfer(address); // send in the address and value via SPI: SPI.transfer(value); - digitalWrite(DIGIPOTSS_PIN, HIGH); // take the SS pin high to de-select the chip: + WRITE(DIGIPOTSS_PIN, HIGH); // take the SS pin high to de-select the chip: //delay(10); } #endif //HAS_DIGIPOTSS -void Stepper::digipot_init() { - #if HAS_DIGIPOTSS - const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT; +#if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM - SPI.begin(); - pinMode(DIGIPOTSS_PIN, OUTPUT); - for (uint8_t i = 0; i < COUNT(digipot_motor_current); i++) { - //digitalPotWrite(digipot_ch[i], digipot_motor_current[i]); - digipot_current(i, digipot_motor_current[i]); - } - #endif - #if HAS_MOTOR_CURRENT_PWM - #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) - pinMode(MOTOR_CURRENT_PWM_XY_PIN, OUTPUT); - digipot_current(0, motor_current_setting[0]); - #endif - #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) - pinMode(MOTOR_CURRENT_PWM_Z_PIN, OUTPUT); - digipot_current(1, motor_current_setting[1]); - #endif - #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) - pinMode(MOTOR_CURRENT_PWM_E_PIN, OUTPUT); - digipot_current(2, motor_current_setting[2]); - #endif - //Set timer5 to 31khz so the PWM of the motor power is as constant as possible. (removes a buzzing noise) - TCCR5B = (TCCR5B & ~(_BV(CS50) | _BV(CS51) | _BV(CS52))) | _BV(CS50); - #endif -} - -void Stepper::digipot_current(uint8_t driver, int current) { - #if HAS_DIGIPOTSS - const uint8_t digipot_ch[] = DIGIPOT_CHANNELS; - digitalPotWrite(digipot_ch[driver], current); - #elif HAS_MOTOR_CURRENT_PWM - #define _WRITE_CURRENT_PWM(P) analogWrite(P, 255L * current / (MOTOR_CURRENT_PWM_RANGE)) - switch (driver) { + void Stepper::digipot_init() { + #if HAS_DIGIPOTSS + static const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT; + SPI.begin(); + SET_OUTPUT(DIGIPOTSS_PIN); + for (uint8_t i = 0; i < COUNT(digipot_motor_current); i++) { + //digitalPotWrite(digipot_ch[i], digipot_motor_current[i]); + digipot_current(i, digipot_motor_current[i]); + } + #elif HAS_MOTOR_CURRENT_PWM #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) - case 0: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_XY_PIN); break; + SET_OUTPUT(MOTOR_CURRENT_PWM_XY_PIN); + digipot_current(0, motor_current_setting[0]); #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) - case 1: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_Z_PIN); break; + SET_OUTPUT(MOTOR_CURRENT_PWM_Z_PIN); + digipot_current(1, motor_current_setting[1]); #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) - case 2: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_E_PIN); break; + SET_OUTPUT(MOTOR_CURRENT_PWM_E_PIN); + digipot_current(2, motor_current_setting[2]); #endif - } - #else - UNUSED(driver); - UNUSED(current); - #endif -} + //Set timer5 to 31khz so the PWM of the motor power is as constant as possible. (removes a buzzing noise) + TCCR5B = (TCCR5B & ~(_BV(CS50) | _BV(CS51) | _BV(CS52))) | _BV(CS50); + #endif + } -void Stepper::microstep_init() { - #if HAS_MICROSTEPS_E1 - pinMode(E1_MS1_PIN, OUTPUT); - pinMode(E1_MS2_PIN, OUTPUT); - #endif + void Stepper::digipot_current(uint8_t driver, int current) { + #if HAS_DIGIPOTSS + const uint8_t digipot_ch[] = DIGIPOT_CHANNELS; + digitalPotWrite(digipot_ch[driver], current); + #elif HAS_MOTOR_CURRENT_PWM + #define _WRITE_CURRENT_PWM(P) analogWrite(P, 255L * current / (MOTOR_CURRENT_PWM_RANGE)) + switch (driver) { + #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) + case 0: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_XY_PIN); break; + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) + case 1: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_Z_PIN); break; + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) + case 2: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_E_PIN); break; + #endif + } + #endif + } - #if HAS_MICROSTEPS - pinMode(X_MS1_PIN, OUTPUT); - pinMode(X_MS2_PIN, OUTPUT); - pinMode(Y_MS1_PIN, OUTPUT); - pinMode(Y_MS2_PIN, OUTPUT); - pinMode(Z_MS1_PIN, OUTPUT); - pinMode(Z_MS2_PIN, OUTPUT); - pinMode(E0_MS1_PIN, OUTPUT); - pinMode(E0_MS2_PIN, OUTPUT); - const uint8_t microstep_modes[] = MICROSTEP_MODES; +#endif + +#if HAS_MICROSTEPS + + /** + * Software-controlled Microstepping + */ + + void Stepper::microstep_init() { + SET_OUTPUT(X_MS1_PIN); + SET_OUTPUT(X_MS2_PIN); + #if HAS_MICROSTEPS_Y + SET_OUTPUT(Y_MS1_PIN); + SET_OUTPUT(Y_MS2_PIN); + #endif + #if HAS_MICROSTEPS_Z + SET_OUTPUT(Z_MS1_PIN); + SET_OUTPUT(Z_MS2_PIN); + #endif + #if HAS_MICROSTEPS_E0 + SET_OUTPUT(E0_MS1_PIN); + SET_OUTPUT(E0_MS2_PIN); + #endif + #if HAS_MICROSTEPS_E1 + SET_OUTPUT(E1_MS1_PIN); + SET_OUTPUT(E1_MS2_PIN); + #endif + static const uint8_t microstep_modes[] = MICROSTEP_MODES; for (uint16_t i = 0; i < COUNT(microstep_modes); i++) microstep_mode(i, microstep_modes[i]); - #endif -} + } -/** - * Software-controlled Microstepping - */ + void Stepper::microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2) { + if (ms1 >= 0) switch (driver) { + case 0: digitalWrite(X_MS1_PIN, ms1); break; + #if HAS_MICROSTEPS_Y + case 1: digitalWrite(Y_MS1_PIN, ms1); break; + #endif + #if HAS_MICROSTEPS_Z + case 2: digitalWrite(Z_MS1_PIN, ms1); break; + #endif + #if HAS_MICROSTEPS_E0 + case 3: digitalWrite(E0_MS1_PIN, ms1); break; + #endif + #if HAS_MICROSTEPS_E1 + case 4: digitalWrite(E1_MS1_PIN, ms1); break; + #endif + } + if (ms2 >= 0) switch (driver) { + case 0: digitalWrite(X_MS2_PIN, ms2); break; + #if HAS_MICROSTEPS_Y + case 1: digitalWrite(Y_MS2_PIN, ms2); break; + #endif + #if HAS_MICROSTEPS_Z + case 2: digitalWrite(Z_MS2_PIN, ms2); break; + #endif + #if HAS_MICROSTEPS_E0 + case 3: digitalWrite(E0_MS2_PIN, ms2); break; + #endif + #if HAS_MICROSTEPS_E1 + case 4: digitalWrite(E1_MS2_PIN, ms2); break; + #endif + } + } -void Stepper::microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2) { - if (ms1 >= 0) switch (driver) { - case 0: digitalWrite(X_MS1_PIN, ms1); break; - case 1: digitalWrite(Y_MS1_PIN, ms1); break; - case 2: digitalWrite(Z_MS1_PIN, ms1); break; - case 3: digitalWrite(E0_MS1_PIN, ms1); break; + void Stepper::microstep_mode(uint8_t driver, uint8_t stepping_mode) { + switch (stepping_mode) { + case 1: microstep_ms(driver, MICROSTEP1); break; + case 2: microstep_ms(driver, MICROSTEP2); break; + case 4: microstep_ms(driver, MICROSTEP4); break; + case 8: microstep_ms(driver, MICROSTEP8); break; + case 16: microstep_ms(driver, MICROSTEP16); break; + } + } + + void Stepper::microstep_readings() { + SERIAL_PROTOCOLLNPGM("MS1,MS2 Pins"); + SERIAL_PROTOCOLPGM("X: "); + SERIAL_PROTOCOL(READ(X_MS1_PIN)); + SERIAL_PROTOCOLLN(READ(X_MS2_PIN)); + #if HAS_MICROSTEPS_Y + SERIAL_PROTOCOLPGM("Y: "); + SERIAL_PROTOCOL(READ(Y_MS1_PIN)); + SERIAL_PROTOCOLLN(READ(Y_MS2_PIN)); + #endif + #if HAS_MICROSTEPS_Z + SERIAL_PROTOCOLPGM("Z: "); + SERIAL_PROTOCOL(READ(Z_MS1_PIN)); + SERIAL_PROTOCOLLN(READ(Z_MS2_PIN)); + #endif + #if HAS_MICROSTEPS_E0 + SERIAL_PROTOCOLPGM("E0: "); + SERIAL_PROTOCOL(READ(E0_MS1_PIN)); + SERIAL_PROTOCOLLN(READ(E0_MS2_PIN)); + #endif #if HAS_MICROSTEPS_E1 - case 4: digitalWrite(E1_MS1_PIN, ms1); break; + SERIAL_PROTOCOLPGM("E1: "); + SERIAL_PROTOCOL(READ(E1_MS1_PIN)); + SERIAL_PROTOCOLLN(READ(E1_MS2_PIN)); #endif } - if (ms2 >= 0) switch (driver) { - case 0: digitalWrite(X_MS2_PIN, ms2); break; - case 1: digitalWrite(Y_MS2_PIN, ms2); break; - case 2: digitalWrite(Z_MS2_PIN, ms2); break; - case 3: digitalWrite(E0_MS2_PIN, ms2); break; - #if PIN_EXISTS(E1_MS2) - case 4: digitalWrite(E1_MS2_PIN, ms2); break; - #endif - } -} -void Stepper::microstep_mode(uint8_t driver, uint8_t stepping_mode) { - switch (stepping_mode) { - case 1: microstep_ms(driver, MICROSTEP1); break; - case 2: microstep_ms(driver, MICROSTEP2); break; - case 4: microstep_ms(driver, MICROSTEP4); break; - case 8: microstep_ms(driver, MICROSTEP8); break; - case 16: microstep_ms(driver, MICROSTEP16); break; - } -} - -void Stepper::microstep_readings() { - SERIAL_PROTOCOLLNPGM("MS1,MS2 Pins"); - SERIAL_PROTOCOLPGM("X: "); - SERIAL_PROTOCOL(digitalRead(X_MS1_PIN)); - SERIAL_PROTOCOLLN(digitalRead(X_MS2_PIN)); - SERIAL_PROTOCOLPGM("Y: "); - SERIAL_PROTOCOL(digitalRead(Y_MS1_PIN)); - SERIAL_PROTOCOLLN(digitalRead(Y_MS2_PIN)); - SERIAL_PROTOCOLPGM("Z: "); - SERIAL_PROTOCOL(digitalRead(Z_MS1_PIN)); - SERIAL_PROTOCOLLN(digitalRead(Z_MS2_PIN)); - SERIAL_PROTOCOLPGM("E0: "); - SERIAL_PROTOCOL(digitalRead(E0_MS1_PIN)); - SERIAL_PROTOCOLLN(digitalRead(E0_MS2_PIN)); - #if HAS_MICROSTEPS_E1 - SERIAL_PROTOCOLPGM("E1: "); - SERIAL_PROTOCOL(digitalRead(E1_MS1_PIN)); - SERIAL_PROTOCOLLN(digitalRead(E1_MS2_PIN)); - #endif -} - -#if ENABLED(LIN_ADVANCE) - - void Stepper::advance_M905(const float &k) { - if (k >= 0) extruder_advance_k = k; - SERIAL_ECHO_START; - SERIAL_ECHOPAIR("Advance factor: ", extruder_advance_k); - SERIAL_EOL; - } - -#endif // LIN_ADVANCE +#endif // HAS_MICROSTEPS diff --git a/Marlin/stepper.h b/Marlin/stepper.h index 1dd1531e4a..7cc323a840 100644 --- a/Marlin/stepper.h +++ b/Marlin/stepper.h @@ -102,19 +102,18 @@ class Stepper { // Counter variables for the Bresenham line tracer static long counter_X, counter_Y, counter_Z, counter_E; - static volatile unsigned long step_events_completed; // The number of step events executed in the current block + static volatile uint32_t step_events_completed; // The number of step events executed in the current block #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) - static unsigned char old_OCR0A; - static volatile unsigned char eISR_Rate; + static uint8_t old_OCR0A; + static volatile uint8_t eISR_Rate; #if ENABLED(LIN_ADVANCE) static volatile int e_steps[E_STEPPERS]; - static int extruder_advance_k; static int final_estep_rate; static int current_estep_rate[E_STEPPERS]; // Actual extruder speed [steps/s] static int current_adv_steps[E_STEPPERS]; // The amount of current added esteps due to advance. - // i.e., the current amount of pressure applied - // to the spring (=filament). + // i.e., the current amount of pressure applied + // to the spring (=filament). #else static long e_steps[E_STEPPERS]; static long advance_rate, advance, final_advance; @@ -128,7 +127,7 @@ class Stepper { static uint8_t step_loops, step_loops_nominal; static unsigned short OCR1A_nominal; - static volatile long endstops_trigsteps[3]; + static volatile long endstops_trigsteps[XYZ]; static volatile long endstops_stepsTotal, endstops_stepsDone; #if HAS_MOTOR_CURRENT_PWM @@ -152,7 +151,7 @@ class Stepper { // Mixing extruder mix counters // #if ENABLED(MIXING_EXTRUDER) - static long counter_M[MIXING_STEPPERS]; + static long counter_m[MIXING_STEPPERS]; #define MIXING_STEPPERS_LOOP(VAR) \ for (uint8_t VAR = 0; VAR < MIXING_STEPPERS; VAR++) \ if (current_block->mix_event_count[VAR]) @@ -188,8 +187,9 @@ class Stepper { // // Set the current position in steps // - static void set_position(const long& x, const long& y, const long& z, const long& e); - static void set_e_position(const long& e); + static void set_position(const long &a, const long &b, const long &c, const long &e); + static void set_position(const AxisEnum &a, const long &v); + static void set_e_position(const long &e); // // Set direction bits for all steppers @@ -211,6 +211,13 @@ class Stepper { // static float get_axis_position_mm(AxisEnum axis); + // + // SCARA AB axes are in degrees, not mm + // + #if IS_SCARA + static FORCE_INLINE float get_axis_position_degrees(AxisEnum axis) { return get_axis_position_mm(axis); } + #endif + // // The stepper subsystem goes to sleep when it runs out of things to execute. Call this // to notify the subsystem that it is time to go to work. @@ -232,13 +239,16 @@ class Stepper { // static FORCE_INLINE bool motor_direction(AxisEnum axis) { return TEST(last_direction_bits, axis); } - #if HAS_DIGIPOTSS + #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM static void digitalPotWrite(int address, int value); + static void digipot_current(uint8_t driver, int current); + #endif + + #if HAS_MICROSTEPS + static void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2); + static void microstep_mode(uint8_t driver, uint8_t stepping); + static void microstep_readings(); #endif - static void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2); - static void digipot_current(uint8_t driver, int current); - static void microstep_mode(uint8_t driver, uint8_t stepping); - static void microstep_readings(); #if ENABLED(Z_DUAL_ENDSTOPS) static FORCE_INLINE void set_homing_flag(bool state) { performing_homing = state; } @@ -247,7 +257,7 @@ class Stepper { #endif #if ENABLED(BABYSTEPPING) - static void babystep(const uint8_t axis, const bool direction); // perform a short step with a single stepper motor, outside of any convention + static void babystep(const AxisEnum axis, const bool direction); // perform a short step with a single stepper motor, outside of any convention #endif static inline void kill_current_block() { @@ -266,11 +276,6 @@ class Stepper { return endstops_trigsteps[axis] * planner.steps_to_mm[axis]; } - #if ENABLED(LIN_ADVANCE) - void advance_M905(const float &k); - FORCE_INLINE int get_advance_k() { return extruder_advance_k; } - #endif - private: static FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) { @@ -356,8 +361,8 @@ class Stepper { #if ENABLED(LIN_ADVANCE) if (current_block->use_advance_lead) { - current_estep_rate[current_block->active_extruder] = ((unsigned long)acc_step_rate * current_block->e_speed_multiplier8) >> 8; - final_estep_rate = (current_block->nominal_rate * current_block->e_speed_multiplier8) >> 8; + current_estep_rate[current_block->active_extruder] = ((unsigned long)acc_step_rate * current_block->abs_adv_steps_multiplier8) >> 17; + final_estep_rate = (current_block->nominal_rate * current_block->abs_adv_steps_multiplier8) >> 17; } #endif @@ -373,8 +378,11 @@ class Stepper { } static void digipot_init(); - static void microstep_init(); + + #if HAS_MICROSTEPS + static void microstep_init(); + #endif }; -#endif // STEPPER_H \ No newline at end of file +#endif // STEPPER_H diff --git a/Marlin/stepper_dac.cpp b/Marlin/stepper_dac.cpp index 6c71b89f64..efdea60a38 100644 --- a/Marlin/stepper_dac.cpp +++ b/Marlin/stepper_dac.cpp @@ -49,11 +49,11 @@ bool dac_present = false; const uint8_t dac_order[NUM_AXIS] = DAC_STEPPER_ORDER; + uint16_t dac_channel_pct[XYZE]; int dac_init() { #if PIN_EXISTS(DAC_DISABLE) - pinMode(DAC_DISABLE_PIN, OUTPUT); - digitalWrite(DAC_DISABLE_PIN, LOW); // set pin low to enable DAC + OUT_WRITE(DAC_DISABLE_PIN, LOW); // set pin low to enable DAC #endif mcp4728_init(); @@ -73,7 +73,7 @@ NOMORE(val, 100); - mcp4728_analogWrite(dac_order[channel], val * DAC_STEPPER_MAX / 100); + mcp4728_analogWrite(dac_order[channel], val * 0.01 * (DAC_STEPPER_MAX)); mcp4728_simpleCommand(UPDATE); } @@ -86,8 +86,14 @@ mcp4728_simpleCommand(UPDATE); } - static float dac_perc(int8_t n) { return 100.0 * mcp4728_getValue(dac_order[n]) / DAC_STEPPER_MAX; } - static float dac_amps(int8_t n) { return ((2.048 * mcp4728_getValue(dac_order[n])) / 4096.0) / (8.0 * DAC_STEPPER_SENSE); } + static float dac_perc(int8_t n) { return 100.0 * mcp4728_getValue(dac_order[n]) * (1.0 / (DAC_STEPPER_MAX)); } + static float dac_amps(int8_t n) { return mcp4728_getDrvPct(dac_order[n]) * (DAC_STEPPER_MAX) * 0.125 * (1.0 / (DAC_STEPPER_SENSE)); } + + int16_t dac_current_get_percent(AxisEnum axis) { return mcp4728_getDrvPct(dac_order[axis]); } + void dac_current_set_percents(int16_t pct[XYZE]) { + LOOP_XYZE(i) dac_channel_pct[i] = pct[dac_order[i]]; + mcp4728_setDrvPct(dac_channel_pct); + } void dac_print_values() { if (!dac_present) return; @@ -95,15 +101,15 @@ SERIAL_ECHO_START; SERIAL_ECHOLNPGM("Stepper current values in % (Amps):"); SERIAL_ECHO_START; - SERIAL_ECHOPAIR(" X:", dac_perc(0)); - SERIAL_ECHOPAIR(" (", dac_amps(0)); - SERIAL_ECHOPAIR(") Y:", dac_perc(1)); - SERIAL_ECHOPAIR(" (", dac_amps(1)); - SERIAL_ECHOPAIR(") Z:", dac_perc(2)); - SERIAL_ECHOPAIR(" (", dac_amps(2)); - SERIAL_ECHOPAIR(") E:", dac_perc(3)); - SERIAL_ECHOPAIR(" (", dac_amps(3)); - SERIAL_ECHOLNPGM(")"); + SERIAL_ECHOPAIR(" X:", dac_perc(X_AXIS)); + SERIAL_ECHOPAIR(" (", dac_amps(X_AXIS)); + SERIAL_ECHOPAIR(") Y:", dac_perc(Y_AXIS)); + SERIAL_ECHOPAIR(" (", dac_amps(Y_AXIS)); + SERIAL_ECHOPAIR(") Z:", dac_perc(Z_AXIS)); + SERIAL_ECHOPAIR(" (", dac_amps(Z_AXIS)); + SERIAL_ECHOPAIR(") E:", dac_perc(E_AXIS)); + SERIAL_ECHOPAIR(" (", dac_amps(E_AXIS)); + SERIAL_ECHOLN(")"); } void dac_commit_eeprom() { diff --git a/Marlin/stepper_dac.h b/Marlin/stepper_dac.h index d80a846709..ab338a2712 100644 --- a/Marlin/stepper_dac.h +++ b/Marlin/stepper_dac.h @@ -51,5 +51,7 @@ void dac_current_percent(uint8_t channel, float val); void dac_current_raw(uint8_t channel, uint16_t val); void dac_print_values(); void dac_commit_eeprom(); +int16_t dac_current_get_percent(AxisEnum axis); +void dac_current_set_percents(int16_t pct[XYZE]); #endif // STEPPER_DAC_H diff --git a/Marlin/stepper_indirection.cpp b/Marlin/stepper_indirection.cpp index 101249e3c8..778f448937 100644 --- a/Marlin/stepper_indirection.cpp +++ b/Marlin/stepper_indirection.cpp @@ -45,201 +45,590 @@ #include "MarlinConfig.h" +// +// TMC26X Driver objects and inits +// #if ENABLED(HAVE_TMCDRIVER) + #include #include -#endif -// Stepper objects of TMC steppers used -#if ENABLED(X_IS_TMC) - TMC26XStepper stepperX(200, X_ENABLE_PIN, X_STEP_PIN, X_DIR_PIN, X_MAX_CURRENT, X_SENSE_RESISTOR); -#endif -#if ENABLED(X2_IS_TMC) - TMC26XStepper stepperX2(200, X2_ENABLE_PIN, X2_STEP_PIN, X2_DIR_PIN, X2_MAX_CURRENT, X2_SENSE_RESISTOR); -#endif -#if ENABLED(Y_IS_TMC) - TMC26XStepper stepperY(200, Y_ENABLE_PIN, Y_STEP_PIN, Y_DIR_PIN, Y_MAX_CURRENT, Y_SENSE_RESISTOR); -#endif -#if ENABLED(Y2_IS_TMC) - TMC26XStepper stepperY2(200, Y2_ENABLE_PIN, Y2_STEP_PIN, Y2_DIR_PIN, Y2_MAX_CURRENT, Y2_SENSE_RESISTOR); -#endif -#if ENABLED(Z_IS_TMC) - TMC26XStepper stepperZ(200, Z_ENABLE_PIN, Z_STEP_PIN, Z_DIR_PIN, Z_MAX_CURRENT, Z_SENSE_RESISTOR); -#endif -#if ENABLED(Z2_IS_TMC) - TMC26XStepper stepperZ2(200, Z2_ENABLE_PIN, Z2_STEP_PIN, Z2_DIR_PIN, Z2_MAX_CURRENT, Z2_SENSE_RESISTOR); -#endif -#if ENABLED(E0_IS_TMC) - TMC26XStepper stepperE0(200, E0_ENABLE_PIN, E0_STEP_PIN, E0_DIR_PIN, E0_MAX_CURRENT, E0_SENSE_RESISTOR); -#endif -#if ENABLED(E1_IS_TMC) - TMC26XStepper stepperE1(200, E1_ENABLE_PIN, E1_STEP_PIN, E1_DIR_PIN, E1_MAX_CURRENT, E1_SENSE_RESISTOR); -#endif -#if ENABLED(E2_IS_TMC) - TMC26XStepper stepperE2(200, E2_ENABLE_PIN, E2_STEP_PIN, E2_DIR_PIN, E2_MAX_CURRENT, E2_SENSE_RESISTOR); -#endif -#if ENABLED(E3_IS_TMC) - TMC26XStepper stepperE3(200, E3_ENABLE_PIN, E3_STEP_PIN, E3_DIR_PIN, E3_MAX_CURRENT, E3_SENSE_RESISTOR); -#endif - -#if ENABLED(HAVE_TMCDRIVER) -void tmc_init() { #if ENABLED(X_IS_TMC) - stepperX.setMicrosteps(X_MICROSTEPS); - stepperX.start(); + TMC26XStepper stepperX(200, X_ENABLE_PIN, X_STEP_PIN, X_DIR_PIN, X_MAX_CURRENT, X_SENSE_RESISTOR); #endif #if ENABLED(X2_IS_TMC) - stepperX2.setMicrosteps(X2_MICROSTEPS); - stepperX2.start(); + TMC26XStepper stepperX2(200, X2_ENABLE_PIN, X2_STEP_PIN, X2_DIR_PIN, X2_MAX_CURRENT, X2_SENSE_RESISTOR); #endif #if ENABLED(Y_IS_TMC) - stepperY.setMicrosteps(Y_MICROSTEPS); - stepperY.start(); + TMC26XStepper stepperY(200, Y_ENABLE_PIN, Y_STEP_PIN, Y_DIR_PIN, Y_MAX_CURRENT, Y_SENSE_RESISTOR); #endif #if ENABLED(Y2_IS_TMC) - stepperY2.setMicrosteps(Y2_MICROSTEPS); - stepperY2.start(); + TMC26XStepper stepperY2(200, Y2_ENABLE_PIN, Y2_STEP_PIN, Y2_DIR_PIN, Y2_MAX_CURRENT, Y2_SENSE_RESISTOR); #endif #if ENABLED(Z_IS_TMC) - stepperZ.setMicrosteps(Z_MICROSTEPS); - stepperZ.start(); + TMC26XStepper stepperZ(200, Z_ENABLE_PIN, Z_STEP_PIN, Z_DIR_PIN, Z_MAX_CURRENT, Z_SENSE_RESISTOR); #endif #if ENABLED(Z2_IS_TMC) - stepperZ2.setMicrosteps(Z2_MICROSTEPS); - stepperZ2.start(); + TMC26XStepper stepperZ2(200, Z2_ENABLE_PIN, Z2_STEP_PIN, Z2_DIR_PIN, Z2_MAX_CURRENT, Z2_SENSE_RESISTOR); #endif #if ENABLED(E0_IS_TMC) - stepperE0.setMicrosteps(E0_MICROSTEPS); - stepperE0.start(); + TMC26XStepper stepperE0(200, E0_ENABLE_PIN, E0_STEP_PIN, E0_DIR_PIN, E0_MAX_CURRENT, E0_SENSE_RESISTOR); #endif #if ENABLED(E1_IS_TMC) - stepperE1.setMicrosteps(E1_MICROSTEPS); - stepperE1.start(); + TMC26XStepper stepperE1(200, E1_ENABLE_PIN, E1_STEP_PIN, E1_DIR_PIN, E1_MAX_CURRENT, E1_SENSE_RESISTOR); #endif #if ENABLED(E2_IS_TMC) - stepperE2.setMicrosteps(E2_MICROSTEPS); - stepperE2.start(); + TMC26XStepper stepperE2(200, E2_ENABLE_PIN, E2_STEP_PIN, E2_DIR_PIN, E2_MAX_CURRENT, E2_SENSE_RESISTOR); #endif #if ENABLED(E3_IS_TMC) - stepperE3.setMicrosteps(E3_MICROSTEPS); - stepperE3.start(); + TMC26XStepper stepperE3(200, E3_ENABLE_PIN, E3_STEP_PIN, E3_DIR_PIN, E3_MAX_CURRENT, E3_SENSE_RESISTOR); #endif -} -#endif + #define _TMC_INIT(A) do{ \ + stepper##A.setMicrosteps(A##_MICROSTEPS); + stepper##A.start(); + } while(0) + + void tmc_init() { + #if ENABLED(X_IS_TMC) + _TMC_INIT(X); + #endif + #if ENABLED(X2_IS_TMC) + _TMC_INIT(X2); + #endif + #if ENABLED(Y_IS_TMC) + _TMC_INIT(Y); + #endif + #if ENABLED(Y2_IS_TMC) + _TMC_INIT(Y2); + #endif + #if ENABLED(Z_IS_TMC) + _TMC_INIT(Z); + #endif + #if ENABLED(Z2_IS_TMC) + _TMC_INIT(Z2); + #endif + #if ENABLED(E0_IS_TMC) + _TMC_INIT(E0); + #endif + #if ENABLED(E1_IS_TMC) + _TMC_INIT(E1); + #endif + #if ENABLED(E2_IS_TMC) + _TMC_INIT(E2); + #endif + #if ENABLED(E3_IS_TMC) + _TMC_INIT(E3); + #endif + } + +#endif // HAVE_TMCDRIVER + +// +// TMC2130 Driver objects and inits +// +#if ENABLED(HAVE_TMC2130DRIVER) + + #include + #include + + #if ENABLED(TMC2130_ADVANCED_CONFIGURATION) + + #ifdef GLOBAL_I_SCALE_ANALOG + #define _2130_set_I_scale_analog(A) stepper##A.set_I_scale_analog(GLOBAL_I_SCALE_ANALOG) + #else + #define _2130_set_I_scale_analog(A) NOOP + #endif + #ifdef GLOBAL_INTERNAL_RSENSE + #define _2130_set_internal_Rsense(A) stepper##A.set_internal_Rsense(GLOBAL_INTERNAL_RSENSE) + #else + #define _2130_set_internal_Rsense(A) NOOP + #endif + #ifdef GLOBAL_EN_PWM_MODE + #define _2130_set_en_pwm_mode(A) stepper##A.set_en_pwm_mode(GLOBAL_EN_PWM_MODE) + #else + #define _2130_set_en_pwm_mode(A) NOOP + #endif + #ifdef GLOBAL_ENC_COMMUTATION + #define _2130_set_enc_commutation(A) stepper##A.set_enc_commutation(GLOBAL_ENC_COMMUTATION) + #else + #define _2130_set_enc_commutation(A) NOOP + #endif + #ifdef GLOBAL_SHAFT + #define _2130_set_shaft(A) stepper##A.set_shaft(GLOBAL_SHAFT) + #else + #define _2130_set_shaft(A) NOOP + #endif + #ifdef GLOBAL_DIAG0_ERROR + #define _2130_set_diag0_error(A) stepper##A.set_diag0_error(GLOBAL_DIAG0_ERROR) + #else + #define _2130_set_diag0_error(A) NOOP + #endif + #ifdef GLOBAL_DIAG0_OTPW + #define _2130_set_diag0_otpw(A) stepper##A.set_diag0_otpw(GLOBAL_DIAG0_OTPW) + #else + #define _2130_set_diag0_otpw(A) NOOP + #endif + #ifdef GLOBAL_DIAG0_STALL + #define _2130_set_diag0_stall(A) stepper##A.set_diag0_stall(GLOBAL_DIAG0_STALL) + #else + #define _2130_set_diag0_stall(A) NOOP + #endif + #ifdef GLOBAL_DIAG1_STALL + #define _2130_set_diag1_stall(A) stepper##A.set_diag1_stall(GLOBAL_DIAG1_STALL) + #else + #define _2130_set_diag1_stall(A) NOOP + #endif + #ifdef GLOBAL_DIAG1_INDEX + #define _2130_set_diag1_index(A) stepper##A.set_diag1_index(GLOBAL_DIAG1_INDEX) + #else + #define _2130_set_diag1_index(A) NOOP + #endif + #ifdef GLOBAL_DIAG1_ONSTATE + #define _2130_set_diag1_onstate(A) stepper##A.set_diag1_onstate(GLOBAL_DIAG1_ONSTATE) + #else + #define _2130_set_diag1_onstate(A) NOOP + #endif + #ifdef GLOBAL_DIAG1_ONSTATE + #define _2130_set_diag1_steps_skipped(A) stepper##A.set_diag1_steps_skipped(GLOBAL_DIAG1_ONSTATE) + #else + #define _2130_set_diag1_steps_skipped(A) NOOP + #endif + #ifdef GLOBAL_DIAG0_INT_PUSHPULL + #define _2130_set_diag0_int_pushpull(A) stepper##A.set_diag0_int_pushpull(GLOBAL_DIAG0_INT_PUSHPULL) + #else + #define _2130_set_diag0_int_pushpull(A) NOOP + #endif + #ifdef GLOBAL_DIAG1_INT_PUSHPULL + #define _2130_set_diag1_int_pushpull(A) stepper##A.set_diag1_int_pushpull(GLOBAL_DIAG1_INT_PUSHPULL) + #else + #define _2130_set_diag1_int_pushpull(A) NOOP + #endif + #ifdef GLOBAL_SMALL_HYSTERESIS + #define _2130_set_small_hysteresis(A) stepper##A.set_small_hysteresis(GLOBAL_SMALL_HYSTERESIS) + #else + #define _2130_set_small_hysteresis(A) NOOP + #endif + #ifdef GLOBAL_STOP_ENABLE + #define _2130_set_stop_enable(A) stepper##A.set_stop_enable(GLOBAL_STOP_ENABLE) + #else + #define _2130_set_stop_enable(A) NOOP + #endif + #ifdef GLOBAL_DIRECT_MODE + #define _2130_set_direct_mode(A) stepper##A.set_direct_mode(GLOBAL_DIRECT_MODE) + #else + #define _2130_set_direct_mode(A) NOOP + #endif + #if defined(GLOBAL_IHOLD) && defined(GLOBAL_IRUN) && defined(GLOBAL_IHOLDDELAY) + #define _2130_set_IHOLD_IRUN(A) stepper##A.set_IHOLD_IRUN(GLOBAL_IHOLD, GLOBAL_IRUN, GLOBAL_IHOLDDELAY) + #else + #define _2130_set_IHOLD_IRUN(A) NOOP + #endif + #ifdef GLOBAL_TPOWERDOWN + #define _2130_set_TPOWERDOWN(A) stepper##A.set_TPOWERDOWN(GLOBAL_TPOWERDOWN) + #else + #define _2130_set_TPOWERDOWN(A) NOOP + #endif + #ifdef GLOBAL_TPWMTHRS + #define _2130_set_TPWMTHRS(A) stepper##A.set_TPWMTHRS(GLOBAL_TPWMTHRS) + #else + #define _2130_set_TPWMTHRS(A) NOOP + #endif + #ifdef GLOBAL_TCOOLTHRS + #define _2130_set_TCOOLTHRS(A) stepper##A.set_TCOOLTHRS(GLOBAL_TCOOLTHRS) + #else + #define _2130_set_TCOOLTHRS(A) NOOP + #endif + #ifdef GLOBAL_THIGH + #define _2130_set_THIGH(A) stepper##A.set_THIGH(GLOBAL_THIGH) + #else + #define _2130_set_THIGH(A) NOOP + #endif + #ifdef GLOBAL_XDIRECT + #define _2130_set_XDIRECT(A) stepper##A.set_XDIRECT(GLOBAL_XDIRECT) + #else + #define _2130_set_XDIRECT(A) NOOP + #endif + #ifdef GLOBAL_VDCMIN + #define _2130_set_VDCMIN(A) stepper##A.set_VDCMIN(GLOBAL_VDCMIN) + #else + #define _2130_set_VDCMIN(A) NOOP + #endif + #ifdef GLOBAL_DEDGE + #define _2130_set_dedge(A) stepper##A.set_dedge(GLOBAL_DEDGE) + #else + #define _2130_set_dedge(A) NOOP + #endif + #ifdef GLOBAL_DISS2G + #define _2130_set_diss2g(A) stepper##A.set_diss2g(GLOBAL_DISS2G) + #else + #define _2130_set_diss2g(A) NOOP + #endif + #ifdef GLOBAL_INTPOL + #define _2130_set_intpol(A) stepper##A.set_intpol(GLOBAL_INTPOL) + #else + #define _2130_set_intpol(A) NOOP + #endif + #ifdef GLOBAL_MRES + #define _2130_set_mres(A) stepper##A.set_mres(GLOBAL_MRES) + #else + #define _2130_set_mres(A) NOOP + #endif + #ifdef GLOBAL_SYNC + #define _2130_set_sync(A) stepper##A.set_sync(GLOBAL_SYNC) + #else + #define _2130_set_sync(A) NOOP + #endif + #ifdef GLOBAL_VHIGHCHM + #define _2130_set_vhighchm(A) stepper##A.set_vhighchm(GLOBAL_VHIGHCHM) + #else + #define _2130_set_vhighchm(A) NOOP + #endif + #ifdef GLOBAL_VHIGHFS + #define _2130_set_vhighfs(A) stepper##A.set_vhighfs(GLOBAL_VHIGHFS) + #else + #define _2130_set_vhighfs(A) NOOP + #endif + #ifdef GLOBAL_VSENSE + #define _2130_set_vsense(A) stepper##A.set_vsense(GLOBAL_VSENSE) + #else + #define _2130_set_vsense(A) NOOP + #endif + #ifdef GLOBAL_TBL + #define _2130_set_tbl(A) stepper##A.set_tbl(GLOBAL_TBL) + #else + #define _2130_set_tbl(A) NOOP + #endif + #ifdef GLOBAL_CHM + #define _2130_set_chm(A) stepper##A.set_chm(GLOBAL_CHM) + #else + #define _2130_set_chm(A) NOOP + #endif + #ifdef GLOBAL_RNDTF + #define _2130_set_rndtf(A) stepper##A.set_rndtf(GLOBAL_RNDTF) + #else + #define _2130_set_rndtf(A) NOOP + #endif + #ifdef GLOBAL_DISFDCC + #define _2130_set_disfdcc(A) stepper##A.set_disfdcc(GLOBAL_DISFDCC) + #else + #define _2130_set_disfdcc(A) NOOP + #endif + #ifdef GLOBAL_FD + #define _2130_set_fd(A) stepper##A.set_fd(GLOBAL_FD) + #else + #define _2130_set_fd(A) NOOP + #endif + #ifdef GLOBAL_HEND + #define _2130_set_hend(A) stepper##A.set_hend(GLOBAL_HEND) + #else + #define _2130_set_hend(A) NOOP + #endif + #ifdef GLOBAL_HSTRT + #define _2130_set_hstrt(A) stepper##A.set_hstrt(GLOBAL_HSTRT) + #else + #define _2130_set_hstrt(A) NOOP + #endif + #ifdef GLOBAL_TOFF + #define _2130_set_toff(A) stepper##A.set_toff(GLOBAL_TOFF) + #else + #define _2130_set_toff(A) NOOP + #endif + #ifdef GLOBAL_SFILT + #define _2130_set_sfilt(A) stepper##A.set_sfilt(GLOBAL_SFILT) + #else + #define _2130_set_sfilt(A) NOOP + #endif + #ifdef GLOBAL_SGT + #define _2130_set_sgt(A) stepper##A.set_sgt(GLOBAL_SGT) + #else + #define _2130_set_sgt(A) NOOP + #endif + #ifdef GLOBAL_SEIMIN + #define _2130_set_seimin(A) stepper##A.set_seimin(GLOBAL_SEIMIN) + #else + #define _2130_set_seimin(A) NOOP + #endif + #ifdef GLOBAL_SEDN + #define _2130_set_sedn(A) stepper##A.set_sedn(GLOBAL_SEDN) + #else + #define _2130_set_sedn(A) NOOP + #endif + #ifdef GLOBAL_SEMAX + #define _2130_set_semax(A) stepper##A.set_semax(GLOBAL_SEMAX) + #else + #define _2130_set_semax(A) NOOP + #endif + #ifdef GLOBAL_SEUP + #define _2130_set_seup(A) stepper##A.set_seup(GLOBAL_SEUP) + #else + #define _2130_set_seup(A) NOOP + #endif + #ifdef GLOBAL_SEMIN + #define _2130_set_semin(A) stepper##A.set_semin(GLOBAL_SEMIN) + #else + #define _2130_set_semin(A) NOOP + #endif + #if defined(GLOBAL_DC_TIME) && defined(GLOBAL_DC_SG) + #define _2130_set_DCCTRL(A) stepper##A.set_DCCTRL(GLOBAL_DC_TIME, GLOBAL_DC_SG) + #else + #define _2130_set_DCCTRL(A) NOOP + #endif + #ifdef GLOBAL_FREEWHEEL + #define _2130_set_freewheel(A) stepper##A.set_freewheel(GLOBAL_FREEWHEEL) + #else + #define _2130_set_freewheel(A) NOOP + #endif + #ifdef GLOBAL_PWM_SYMMETRIC + #define _2130_set_pwm_symmetric(A) stepper##A.set_pwm_symmetric(GLOBAL_PWM_SYMMETRIC) + #else + #define _2130_set_pwm_symmetric(A) NOOP + #endif + #ifdef GLOBAL_PWM_AUTOSCALE + #define _2130_set_pwm_autoscale(A) stepper##A.set_pwm_autoscale(GLOBAL_PWM_AUTOSCALE) + #else + #define _2130_set_pwm_autoscale(A) NOOP + #endif + #ifdef GLOBAL_PWM_FREQ + #define _2130_set_pwm_freq(A) stepper##A.set_pwm_freq(GLOBAL_PWM_FREQ) + #else + #define _2130_set_pwm_freq(A) NOOP + #endif + #ifdef GLOBAL_PWM_GRAD + #define _2130_set_PWM_GRAD(A) stepper##A.set_PWM_GRAD(GLOBAL_PWM_GRAD) + #else + #define _2130_set_PWM_GRAD(A) NOOP + #endif + #ifdef GLOBAL_PWM_AMPL + #define _2130_set_PWM_AMPL(A) stepper##A.set_PWM_AMPL(GLOBAL_PWM_AMPL) + #else + #define _2130_set_PWM_AMPL(A) NOOP + #endif + #ifdef GLOBAL_ENCM_CTRL + #define _2130_set_ENCM_CTRL(A) stepper##A.set_ENCM_CTRL(GLOBAL_ENCM_CTRL) + #else + #define _2130_set_ENCM_CTRL(A) NOOP + #endif + + #define _TMC2130_INIT(A) do{ \ + stepper##A.init(); \ + _2130_set_I_scale_analog(A); \ + _2130_set_internal_Rsense(A); \ + _2130_set_en_pwm_mode(A); \ + _2130_set_enc_commutation(A); \ + _2130_set_shaft(A); \ + _2130_set_diag0_error(A); \ + _2130_set_diag0_otpw(A); \ + _2130_set_diag0_stall(A); \ + _2130_set_diag1_stall(A); \ + _2130_set_diag1_index(A); \ + _2130_set_diag1_onstate(A); \ + _2130_set_diag1_steps_skipped(A); \ + _2130_set_diag0_int_pushpull(A); \ + _2130_set_diag1_int_pushpull(A); \ + _2130_set_small_hysteresis(A); \ + _2130_set_stop_enable(A); \ + _2130_set_direct_mode(A); \ + _2130_set_IHOLD_IRUN(A); \ + _2130_set_TPOWERDOWN(A); \ + _2130_set_TPWMTHRS(A); \ + _2130_set_TCOOLTHRS(A); \ + _2130_set_THIGH(A); \ + _2130_set_XDIRECT(A); \ + _2130_set_VDCMIN(A); \ + _2130_set_dedge(A); \ + _2130_set_diss2g(A); \ + _2130_set_intpol(A); \ + _2130_set_mres(A); \ + _2130_set_sync(A); \ + _2130_set_vhighchm(A); \ + _2130_set_vhighfs(A); \ + _2130_set_vsense(A); \ + _2130_set_tbl(A); \ + _2130_set_chm(A); \ + _2130_set_rndtf(A); \ + _2130_set_disfdcc(A); \ + _2130_set_fd(A); \ + _2130_set_hend(A); \ + _2130_set_hstrt(A); \ + _2130_set_toff(A); \ + _2130_set_sfilt(A); \ + _2130_set_sgt(A); \ + _2130_set_seimin(A); \ + _2130_set_sedn(A); \ + _2130_set_semax(A); \ + _2130_set_seup(A); \ + _2130_set_semin(A); \ + _2130_set_DCCTRL(A); \ + _2130_set_freewheel(A); \ + _2130_set_pwm_symmetric(A); \ + _2130_set_pwm_autoscale(A); \ + _2130_set_pwm_freq(A); \ + _2130_set_PWM_GRAD(A); \ + _2130_set_PWM_AMPL(A); \ + _2130_set_ENCM_CTRL(A); \ + } while(0) + + #else // !TMC2130_ADVANCED_CONFIGURATION + + #define _TMC2130_INIT(A) do{ \ + stepper##A.init(); \ + stepper##A.set_mres(A##_MRES); \ + stepper##A.set_IHOLD_IRUN(A##_IHOLD, A##_IRUN, A##_IHOLDDELAY); \ + stepper##A.set_I_scale_analog(A##_I_SCALE_ANALOG); \ + stepper##A.set_tbl(A##_TBL); \ + stepper##A.set_toff(A##_TOFF); \ + } while(0) + + #endif // TMC2130_ADVANCED_CONFIGURATION + + // Stepper objects of TMC2310 steppers used + #if ENABLED(X_IS_TMC2130) + Trinamic_TMC2130 stepperX(X_CS_PIN); + #endif + #if ENABLED(X2_IS_TMC2130) + Trinamic_TMC2130 stepperX2(X2_CS_PIN); + #endif + #if ENABLED(Y_IS_TMC2130) + Trinamic_TMC2130 stepperY(Y_CS_PIN); + #endif + #if ENABLED(Y2_IS_TMC2130) + Trinamic_TMC2130 stepperY2(Y2_CS_PINR); + #endif + #if ENABLED(Z_IS_TMC2130) + Trinamic_TMC2130 stepperZ(Z_CS_PIN); + #endif + #if ENABLED(Z2_IS_TMC2130) + Trinamic_TMC2130 stepperZ2(Z2_CS_PIN); + #endif + #if ENABLED(E0_IS_TMC2130) + Trinamic_TMC2130 stepperE0(E0_CS_PIN); + #endif + #if ENABLED(E1_IS_TMC2130) + Trinamic_TMC2130 stepperE1(E1_CS_PIN); + #endif + #if ENABLED(E2_IS_TMC2130) + Trinamic_TMC2130 stepperE2(E2_CS_PIN); + #endif + #if ENABLED(E3_IS_TMC2130) + Trinamic_TMC2130 stepperE3(E3_CS_PIN); + #endif + + void tmc2130_init() { + #if ENABLED(X_IS_TMC2130) + _TMC2130_INIT(X); + #endif + #if ENABLED(X2_IS_TMC2130) + _TMC2130_INIT(X2); + #endif + #if ENABLED(Y_IS_TMC2130) + _TMC2130_INIT(Y); + #endif + #if ENABLED(Y2_IS_TMC2130) + _TMC2130_INIT(Y2); + #endif + #if ENABLED(Z_IS_TMC2130) + _TMC2130_INIT(Z); + #endif + #if ENABLED(Z2_IS_TMC2130) + _TMC2130_INIT(Z2); + #endif + #if ENABLED(E0_IS_TMC2130) + _TMC2130_INIT(E0); + #endif + #if ENABLED(E1_IS_TMC2130) + _TMC2130_INIT(E1); + #endif + #if ENABLED(E2_IS_TMC2130) + _TMC2130_INIT(E2); + #endif + #if ENABLED(E3_IS_TMC2130) + _TMC2130_INIT(E3); + #endif + } + +#endif // HAVE_TMC2130DRIVER + +// // L6470 Driver objects and inits - +// #if ENABLED(HAVE_L6470DRIVER) + #include #include -#endif -// L6470 Stepper objects -#if ENABLED(X_IS_L6470) - L6470 stepperX(X_ENABLE_PIN); -#endif -#if ENABLED(X2_IS_L6470) - L6470 stepperX2(X2_ENABLE_PIN); -#endif -#if ENABLED(Y_IS_L6470) - L6470 stepperY(Y_ENABLE_PIN); -#endif -#if ENABLED(Y2_IS_L6470) - L6470 stepperY2(Y2_ENABLE_PIN); -#endif -#if ENABLED(Z_IS_L6470) - L6470 stepperZ(Z_ENABLE_PIN); -#endif -#if ENABLED(Z2_IS_L6470) - L6470 stepperZ2(Z2_ENABLE_PIN); -#endif -#if ENABLED(E0_IS_L6470) - L6470 stepperE0(E0_ENABLE_PIN); -#endif -#if ENABLED(E1_IS_L6470) - L6470 stepperE1(E1_ENABLE_PIN); -#endif -#if ENABLED(E2_IS_L6470) - L6470 stepperE2(E2_ENABLE_PIN); -#endif -#if ENABLED(E3_IS_L6470) - L6470 stepperE3(E3_ENABLE_PIN); -#endif - - -// init routine -#if ENABLED(HAVE_L6470DRIVER) -void L6470_init() { + // L6470 Stepper objects #if ENABLED(X_IS_L6470) - stepperX.init(X_K_VAL); - stepperX.softFree(); - stepperX.setMicroSteps(X_MICROSTEPS); - stepperX.setOverCurrent(X_OVERCURRENT); //set overcurrent protection - stepperX.setStallCurrent(X_STALLCURRENT); + L6470 stepperX(X_ENABLE_PIN); #endif #if ENABLED(X2_IS_L6470) - stepperX2.init(X2_K_VAL); - stepperX2.softFree(); - stepperX2.setMicroSteps(X2_MICROSTEPS); - stepperX2.setOverCurrent(X2_OVERCURRENT); //set overcurrent protection - stepperX2.setStallCurrent(X2_STALLCURRENT); + L6470 stepperX2(X2_ENABLE_PIN); #endif #if ENABLED(Y_IS_L6470) - stepperY.init(Y_K_VAL); - stepperY.softFree(); - stepperY.setMicroSteps(Y_MICROSTEPS); - stepperY.setOverCurrent(Y_OVERCURRENT); //set overcurrent protection - stepperY.setStallCurrent(Y_STALLCURRENT); + L6470 stepperY(Y_ENABLE_PIN); #endif #if ENABLED(Y2_IS_L6470) - stepperY2.init(Y2_K_VAL); - stepperY2.softFree(); - stepperY2.setMicroSteps(Y2_MICROSTEPS); - stepperY2.setOverCurrent(Y2_OVERCURRENT); //set overcurrent protection - stepperY2.setStallCurrent(Y2_STALLCURRENT); + L6470 stepperY2(Y2_ENABLE_PIN); #endif #if ENABLED(Z_IS_L6470) - stepperZ.init(Z_K_VAL); - stepperZ.softFree(); - stepperZ.setMicroSteps(Z_MICROSTEPS); - stepperZ.setOverCurrent(Z_OVERCURRENT); //set overcurrent protection - stepperZ.setStallCurrent(Z_STALLCURRENT); + L6470 stepperZ(Z_ENABLE_PIN); #endif #if ENABLED(Z2_IS_L6470) - stepperZ2.init(Z2_K_VAL); - stepperZ2.softFree(); - stepperZ2.setMicroSteps(Z2_MICROSTEPS); - stepperZ2.setOverCurrent(Z2_OVERCURRENT); //set overcurrent protection - stepperZ2.setStallCurrent(Z2_STALLCURRENT); + L6470 stepperZ2(Z2_ENABLE_PIN); #endif #if ENABLED(E0_IS_L6470) - stepperE0.init(E0_K_VAL); - stepperE0.softFree(); - stepperE0.setMicroSteps(E0_MICROSTEPS); - stepperE0.setOverCurrent(E0_OVERCURRENT); //set overcurrent protection - stepperE0.setStallCurrent(E0_STALLCURRENT); + L6470 stepperE0(E0_ENABLE_PIN); #endif #if ENABLED(E1_IS_L6470) - stepperE1.init(E1_K_VAL); - stepperE1.softFree(); - stepperE1.setMicroSteps(E1_MICROSTEPS); - stepperE1.setOverCurrent(E1_OVERCURRENT); //set overcurrent protection - stepperE1.setStallCurrent(E1_STALLCURRENT); + L6470 stepperE1(E1_ENABLE_PIN); #endif #if ENABLED(E2_IS_L6470) - stepperE2.init(E2_K_VAL); - stepperE2.softFree(); - stepperE2.setMicroSteps(E2_MICROSTEPS); - stepperE2.setOverCurrent(E2_OVERCURRENT); //set overcurrent protection - stepperE2.setStallCurrent(E2_STALLCURRENT); + L6470 stepperE2(E2_ENABLE_PIN); #endif #if ENABLED(E3_IS_L6470) - stepperE3.init(E3_K_VAL); - stepperE3.softFree(); - stepperE3.setMicroSteps(E3_MICROSTEPS); - stepperE3.setOverCurrent(E3_OVERCURRENT); //set overcurrent protection - stepperE3.setStallCurrent(E3_STALLCURRENT); + L6470 stepperE3(E3_ENABLE_PIN); #endif -} -#endif + + #define _L6470_INIT(A) do{ \ + stepper##A.init(A##_K_VAL); \ + stepper##A.softFree(); \ + stepper##A.setMicroSteps(A##_MICROSTEPS); \ + stepper##A.setOverCurrent(A##_OVERCURRENT); \ + stepper##A.setStallCurrent(A##_STALLCURRENT); \ + } while(0) + + void L6470_init() { + #if ENABLED(X_IS_L6470) + _L6470_INIT(X); + #endif + #if ENABLED(X2_IS_L6470) + _L6470_INIT(X2); + #endif + #if ENABLED(Y_IS_L6470) + _L6470_INIT(Y); + #endif + #if ENABLED(Y2_IS_L6470) + _L6470_INIT(Y2); + #endif + #if ENABLED(Z_IS_L6470) + _L6470_INIT(Z); + #endif + #if ENABLED(Z2_IS_L6470) + _L6470_INIT(Z2); + #endif + #if ENABLED(E0_IS_L6470) + _L6470_INIT(E0); + #endif + #if ENABLED(E1_IS_L6470) + _L6470_INIT(E1); + #endif + #if ENABLED(E2_IS_L6470) + _L6470_INIT(E2); + #endif + #if ENABLED(E3_IS_L6470) + _L6470_INIT(E3); + #endif + } + +#endif // HAVE_L6470DRIVER diff --git a/Marlin/stepper_indirection.h b/Marlin/stepper_indirection.h index 6fd19dd4d5..0dc941bd14 100644 --- a/Marlin/stepper_indirection.h +++ b/Marlin/stepper_indirection.h @@ -53,6 +53,13 @@ void tmc_init(); #endif +// TMC130 drivers have STEP/DIR/ENABLE on normal pins +#if ENABLED(HAVE_TMC2130DRIVER) + #include + #include + void tmc2130_init(); +#endif + // L6470 has STEP on normal pins, but DIR/ENABLE via SPI #if ENABLED(HAVE_L6470DRIVER) #include @@ -76,6 +83,9 @@ #define X_ENABLE_WRITE(STATE) stepperX.setEnabled(STATE) #define X_ENABLE_READ stepperX.isEnabled() #else + #if ENABLED(HAVE_TMC2130DRIVER) && ENABLED(X_IS_TMC2130) + extern Trinamic_TMC2130 stepperX; + #endif #define X_ENABLE_INIT SET_OUTPUT(X_ENABLE_PIN) #define X_ENABLE_WRITE(STATE) WRITE(X_ENABLE_PIN,STATE) #define X_ENABLE_READ READ(X_ENABLE_PIN) @@ -104,6 +114,9 @@ #define Y_ENABLE_WRITE(STATE) stepperY.setEnabled(STATE) #define Y_ENABLE_READ stepperY.isEnabled() #else + #if ENABLED(HAVE_TMC2130DRIVER) && ENABLED(Y_IS_TMC2130) + extern Trinamic_TMC2130 stepperY; + #endif #define Y_ENABLE_INIT SET_OUTPUT(Y_ENABLE_PIN) #define Y_ENABLE_WRITE(STATE) WRITE(Y_ENABLE_PIN,STATE) #define Y_ENABLE_READ READ(Y_ENABLE_PIN) @@ -132,6 +145,9 @@ #define Z_ENABLE_WRITE(STATE) stepperZ.setEnabled(STATE) #define Z_ENABLE_READ stepperZ.isEnabled() #else + #if ENABLED(HAVE_TMC2130DRIVER) && ENABLED(Z_IS_TMC2130) + extern Trinamic_TMC2130 stepperZ; + #endif #define Z_ENABLE_INIT SET_OUTPUT(Z_ENABLE_PIN) #define Z_ENABLE_WRITE(STATE) WRITE(Z_ENABLE_PIN,STATE) #define Z_ENABLE_READ READ(Z_ENABLE_PIN) @@ -161,6 +177,9 @@ #define X2_ENABLE_WRITE(STATE) stepperX2.setEnabled(STATE) #define X2_ENABLE_READ stepperX2.isEnabled() #else + #if ENABLED(HAVE_TMC2130DRIVER) && ENABLED(X2_IS_TMC2130) + extern Trinamic_TMC2130 stepperX2; + #endif #define X2_ENABLE_INIT SET_OUTPUT(X2_ENABLE_PIN) #define X2_ENABLE_WRITE(STATE) WRITE(X2_ENABLE_PIN,STATE) #define X2_ENABLE_READ READ(X2_ENABLE_PIN) @@ -191,6 +210,9 @@ #define Y2_ENABLE_WRITE(STATE) stepperY2.setEnabled(STATE) #define Y2_ENABLE_READ stepperY2.isEnabled() #else + #if ENABLED(HAVE_TMC2130DRIVER) && ENABLED(Y2_IS_TMC2130) + extern Trinamic_TMC2130 stepperY2; + #endif #define Y2_ENABLE_INIT SET_OUTPUT(Y2_ENABLE_PIN) #define Y2_ENABLE_WRITE(STATE) WRITE(Y2_ENABLE_PIN,STATE) #define Y2_ENABLE_READ READ(Y2_ENABLE_PIN) @@ -221,6 +243,9 @@ #define Z2_ENABLE_WRITE(STATE) stepperZ2.setEnabled(STATE) #define Z2_ENABLE_READ stepperZ2.isEnabled() #else + #if ENABLED(HAVE_TMC2130DRIVER) && ENABLED(Z2_IS_TMC2130) + extern Trinamic_TMC2130 stepperZ2; + #endif #define Z2_ENABLE_INIT SET_OUTPUT(Z2_ENABLE_PIN) #define Z2_ENABLE_WRITE(STATE) WRITE(Z2_ENABLE_PIN,STATE) #define Z2_ENABLE_READ READ(Z2_ENABLE_PIN) @@ -250,6 +275,9 @@ #define E0_ENABLE_WRITE(STATE) stepperE0.setEnabled(STATE) #define E0_ENABLE_READ stepperE0.isEnabled() #else + #if ENABLED(HAVE_TMC2130DRIVER) && ENABLED(E0_IS_TMC2130) + extern Trinamic_TMC2130 stepperE0; + #endif #define E0_ENABLE_INIT SET_OUTPUT(E0_ENABLE_PIN) #define E0_ENABLE_WRITE(STATE) WRITE(E0_ENABLE_PIN,STATE) #define E0_ENABLE_READ READ(E0_ENABLE_PIN) @@ -278,6 +306,9 @@ #define E1_ENABLE_WRITE(STATE) stepperE1.setEnabled(STATE) #define E1_ENABLE_READ stepperE1.isEnabled() #else + #if ENABLED(HAVE_TMC2130DRIVER) && ENABLED(E1_IS_TMC2130) + extern Trinamic_TMC2130 stepperE1; + #endif #define E1_ENABLE_INIT SET_OUTPUT(E1_ENABLE_PIN) #define E1_ENABLE_WRITE(STATE) WRITE(E1_ENABLE_PIN,STATE) #define E1_ENABLE_READ READ(E1_ENABLE_PIN) @@ -306,6 +337,9 @@ #define E2_ENABLE_WRITE(STATE) stepperE2.setEnabled(STATE) #define E2_ENABLE_READ stepperE2.isEnabled() #else + #if ENABLED(HAVE_TMC2130DRIVER) && ENABLED(E2_IS_TMC2130) + extern Trinamic_TMC2130 stepperE2; + #endif #define E2_ENABLE_INIT SET_OUTPUT(E2_ENABLE_PIN) #define E2_ENABLE_WRITE(STATE) WRITE(E2_ENABLE_PIN,STATE) #define E2_ENABLE_READ READ(E2_ENABLE_PIN) @@ -334,6 +368,9 @@ #define E3_ENABLE_WRITE(STATE) stepperE3.setEnabled(STATE) #define E3_ENABLE_READ stepperE3.isEnabled() #else + #if ENABLED(HAVE_TMC2130DRIVER) && ENABLED(E3_IS_TMC2130) + extern Trinamic_TMC2130 stepperE3; + #endif #define E3_ENABLE_INIT SET_OUTPUT(E3_ENABLE_PIN) #define E3_ENABLE_WRITE(STATE) WRITE(E3_ENABLE_PIN,STATE) #define E3_ENABLE_READ READ(E3_ENABLE_PIN) diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 552ef8b2d8..4895d1da9c 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -64,10 +64,10 @@ int Temperature::current_temperature_raw[HOTENDS] = { 0 }, float Temperature::redundant_temperature = 0.0; #endif -unsigned char Temperature::soft_pwm_bed; +uint8_t Temperature::soft_pwm_bed; #if ENABLED(FAN_SOFT_PWM) - unsigned char Temperature::fanSpeedSoftPwm[FAN_COUNT]; + uint8_t Temperature::fanSpeedSoftPwm[FAN_COUNT]; #endif #if ENABLED(PIDTEMP) @@ -95,7 +95,7 @@ unsigned char Temperature::soft_pwm_bed; #endif #if ENABLED(BABYSTEPPING) - volatile int Temperature::babystepsTodo[3] = { 0 }; + volatile int Temperature::babystepsTodo[XYZ] = { 0 }; #endif #if ENABLED(THERMAL_PROTECTION_HOTENDS) && WATCH_TEMP_PERIOD > 0 @@ -108,7 +108,7 @@ unsigned char Temperature::soft_pwm_bed; millis_t Temperature::watch_bed_next_ms = 0; #endif -#if ENABLED(PREVENT_DANGEROUS_EXTRUDE) +#if ENABLED(PREVENT_COLD_EXTRUSION) bool Temperature::allow_cold_extrude = false; float Temperature::extrude_min_temp = EXTRUDE_MINTEMP; #endif @@ -136,9 +136,7 @@ volatile bool Temperature::temp_meas_ready = false; int Temperature::lpq_ptr = 0; #endif - float Temperature::pid_error[HOTENDS], - Temperature::temp_iState_min[HOTENDS], - Temperature::temp_iState_max[HOTENDS]; + float Temperature::pid_error[HOTENDS]; bool Temperature::pid_reset[HOTENDS]; #endif @@ -148,14 +146,12 @@ volatile bool Temperature::temp_meas_ready = false; Temperature::pTerm_bed, Temperature::iTerm_bed, Temperature::dTerm_bed, - Temperature::pid_error_bed, - Temperature::temp_iState_min_bed, - Temperature::temp_iState_max_bed; + Temperature::pid_error_bed; #else millis_t Temperature::next_bed_check_ms; #endif -unsigned long Temperature::raw_temp_value[4] = { 0 }; +unsigned long Temperature::raw_temp_value[MAX_EXTRUDERS] = { 0 }; unsigned long Temperature::raw_temp_bed_value = 0; // Init min and max temp with extreme values to prevent false errors during startup @@ -185,13 +181,13 @@ int Temperature::minttemp_raw[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_RAW_LO_TEMP , #endif #if HAS_AUTO_FAN - millis_t Temperature::next_auto_fan_check_ms; + millis_t Temperature::next_auto_fan_check_ms = 0; #endif -unsigned char Temperature::soft_pwm[HOTENDS]; +uint8_t Temperature::soft_pwm[HOTENDS]; #if ENABLED(FAN_SOFT_PWM) - unsigned char Temperature::soft_pwm_fan[FAN_COUNT]; + uint8_t Temperature::soft_pwm_fan[FAN_COUNT]; #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) @@ -240,13 +236,13 @@ unsigned char Temperature::soft_pwm[HOTENDS]; #if HAS_PID_FOR_BOTH if (hotend < 0) - soft_pwm_bed = bias = d = (MAX_BED_POWER) / 2; + soft_pwm_bed = bias = d = (MAX_BED_POWER) >> 1; else - soft_pwm[hotend] = bias = d = (PID_MAX) / 2; + soft_pwm[hotend] = bias = d = (PID_MAX) >> 1; #elif ENABLED(PIDTEMP) - soft_pwm[hotend] = bias = d = (PID_MAX) / 2; + soft_pwm[hotend] = bias = d = (PID_MAX) >> 1; #else - soft_pwm_bed = bias = d = (MAX_BED_POWER) / 2; + soft_pwm_bed = bias = d = (MAX_BED_POWER) >> 1; #endif wait_for_heatup = true; @@ -269,8 +265,8 @@ unsigned char Temperature::soft_pwm[HOTENDS]; #endif ; - max = max(max, input); - min = min(min, input); + NOLESS(max, input); + NOMORE(min, input); #if HAS_AUTO_FAN if (ELAPSED(ms, next_auto_fan_check_ms)) { @@ -322,17 +318,17 @@ unsigned char Temperature::soft_pwm[HOTENDS]; SERIAL_PROTOCOLPAIR(MSG_T_MIN, min); SERIAL_PROTOCOLPAIR(MSG_T_MAX, max); if (cycles > 2) { - Ku = (4.0 * d) / (3.14159265 * (max - min) * 0.5); + Ku = (4.0 * d) / (M_PI * (max - min) * 0.5); Tu = ((float)(t_low + t_high) * 0.001); SERIAL_PROTOCOLPAIR(MSG_KU, Ku); SERIAL_PROTOCOLPAIR(MSG_TU, Tu); workKp = 0.6 * Ku; workKi = 2 * workKp / Tu; workKd = workKp * Tu * 0.125; - SERIAL_PROTOCOLLNPGM(MSG_CLASSIC_PID); + SERIAL_PROTOCOLLNPGM("\n" MSG_CLASSIC_PID); SERIAL_PROTOCOLPAIR(MSG_KP, workKp); SERIAL_PROTOCOLPAIR(MSG_KI, workKi); - SERIAL_PROTOCOLPAIR(MSG_KD, workKd); + SERIAL_PROTOCOLLNPAIR(MSG_KD, workKd); /** workKp = 0.33*Ku; workKi = workKp/Tu; @@ -390,40 +386,38 @@ unsigned char Temperature::soft_pwm[HOTENDS]; #if HAS_PID_FOR_BOTH const char* estring = hotend < 0 ? "bed" : ""; - SERIAL_PROTOCOLPAIR("#define DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Kp ", workKp); - SERIAL_PROTOCOLPAIR("#define DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Ki ", workKi); - SERIAL_PROTOCOLPAIR("#define DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Kd ", workKd); + SERIAL_PROTOCOLPAIR("#define DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Kp ", workKp); SERIAL_EOL; + SERIAL_PROTOCOLPAIR("#define DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Ki ", workKi); SERIAL_EOL; + SERIAL_PROTOCOLPAIR("#define DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Kd ", workKd); SERIAL_EOL; #elif ENABLED(PIDTEMP) - SERIAL_PROTOCOLPAIR("#define DEFAULT_Kp ", workKp); - SERIAL_PROTOCOLPAIR("#define DEFAULT_Ki ", workKi); - SERIAL_PROTOCOLPAIR("#define DEFAULT_Kd ", workKd); + SERIAL_PROTOCOLPAIR("#define DEFAULT_Kp ", workKp); SERIAL_EOL; + SERIAL_PROTOCOLPAIR("#define DEFAULT_Ki ", workKi); SERIAL_EOL; + SERIAL_PROTOCOLPAIR("#define DEFAULT_Kd ", workKd); SERIAL_EOL; #else - SERIAL_PROTOCOLPAIR("#define DEFAULT_bedKp ", workKp); - SERIAL_PROTOCOLPAIR("#define DEFAULT_bedKi ", workKi); - SERIAL_PROTOCOLPAIR("#define DEFAULT_bedKd ", workKd); + SERIAL_PROTOCOLPAIR("#define DEFAULT_bedKp ", workKp); SERIAL_EOL; + SERIAL_PROTOCOLPAIR("#define DEFAULT_bedKi ", workKi); SERIAL_EOL; + SERIAL_PROTOCOLPAIR("#define DEFAULT_bedKd ", workKd); SERIAL_EOL; #endif - #define _SET_BED_PID() \ + #define _SET_BED_PID() do { \ bedKp = workKp; \ bedKi = scalePID_i(workKi); \ bedKd = scalePID_d(workKd); \ - updatePID() + updatePID(); } while(0) - #define _SET_EXTRUDER_PID() \ + #define _SET_EXTRUDER_PID() do { \ PID_PARAM(Kp, hotend) = workKp; \ PID_PARAM(Ki, hotend) = scalePID_i(workKi); \ PID_PARAM(Kd, hotend) = scalePID_d(workKd); \ - updatePID() + updatePID(); } while(0) // Use the result? (As with "M303 U1") if (set_result) { #if HAS_PID_FOR_BOTH - if (hotend < 0) { + if (hotend < 0) _SET_BED_PID(); - } - else { + else _SET_EXTRUDER_PID(); - } #elif ENABLED(PIDTEMP) _SET_EXTRUDER_PID(); #else @@ -450,12 +444,6 @@ void Temperature::updatePID() { #if ENABLED(PID_EXTRUSION_SCALING) last_e_position = 0; #endif - HOTEND_LOOP() { - temp_iState_max[e] = (PID_INTEGRAL_DRIVE_MAX) / PID_PARAM(Ki, e); - } - #endif - #if ENABLED(PIDTEMPBED) - temp_iState_max_bed = (PID_BED_INTEGRAL_DRIVE_MAX) / bedKi; #endif } @@ -466,25 +454,25 @@ int Temperature::getHeaterPower(int heater) { #if HAS_AUTO_FAN void Temperature::checkExtruderAutoFans() { - const int8_t fanPin[] = { EXTRUDER_0_AUTO_FAN_PIN, EXTRUDER_1_AUTO_FAN_PIN, EXTRUDER_2_AUTO_FAN_PIN, EXTRUDER_3_AUTO_FAN_PIN }; - const int fanBit[] = { 0, - EXTRUDER_1_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN ? 0 : 1, - EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN ? 0 : - EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN ? 1 : 2, - EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN ? 0 : - EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN ? 1 : - EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_2_AUTO_FAN_PIN ? 2 : 3 + const int8_t fanPin[] = { E0_AUTO_FAN_PIN, E1_AUTO_FAN_PIN, E2_AUTO_FAN_PIN, E3_AUTO_FAN_PIN }; + const int fanBit[] = { + 0, + AUTO_1_IS_0 ? 0 : 1, + AUTO_2_IS_0 ? 0 : AUTO_2_IS_1 ? 1 : 2, + AUTO_3_IS_0 ? 0 : AUTO_3_IS_1 ? 1 : AUTO_3_IS_2 ? 2 : 3 }; uint8_t fanState = 0; + HOTEND_LOOP() { if (current_temperature[e] > EXTRUDER_AUTO_FAN_TEMPERATURE) SBI(fanState, fanBit[e]); } + uint8_t fanDone = 0; - for (int8_t f = 0; f <= 3; f++) { + for (uint8_t f = 0; f < COUNT(fanPin); f++) { int8_t pin = fanPin[f]; if (pin >= 0 && !TEST(fanDone, fanBit[f])) { - unsigned char newFanSpeed = TEST(fanState, fanBit[f]) ? EXTRUDER_AUTO_FAN_SPEED : 0; + uint8_t newFanSpeed = TEST(fanState, fanBit[f]) ? EXTRUDER_AUTO_FAN_SPEED : 0; // this idiom allows both digital and PWM fan outputs (see M42 handling). digitalWrite(pin, newFanSpeed); analogWrite(pin, newFanSpeed); @@ -517,17 +505,25 @@ void Temperature::_temp_error(int e, const char* serial_msg, const char* lcd_msg #endif } -void Temperature::max_temp_error(uint8_t e) { - #if HOTENDS == 1 - UNUSED(e); +void Temperature::max_temp_error(int8_t e) { + #if HAS_TEMP_BED + _temp_error(e, PSTR(MSG_T_MAXTEMP), e >= 0 ? PSTR(MSG_ERR_MAXTEMP) : PSTR(MSG_ERR_MAXTEMP_BED)); + #else + _temp_error(HOTEND_INDEX, PSTR(MSG_T_MAXTEMP), PSTR(MSG_ERR_MAXTEMP)); + #if HOTENDS == 1 + UNUSED(e); + #endif #endif - _temp_error(HOTEND_INDEX, PSTR(MSG_T_MAXTEMP), PSTR(MSG_ERR_MAXTEMP)); } -void Temperature::min_temp_error(uint8_t e) { - #if HOTENDS == 1 - UNUSED(e); +void Temperature::min_temp_error(int8_t e) { + #if HAS_TEMP_BED + _temp_error(e, PSTR(MSG_T_MINTEMP), e >= 0 ? PSTR(MSG_ERR_MINTEMP) : PSTR(MSG_ERR_MINTEMP_BED)); + #else + _temp_error(HOTEND_INDEX, PSTR(MSG_T_MINTEMP), PSTR(MSG_ERR_MINTEMP)); + #if HOTENDS == 1 + UNUSED(e); + #endif #endif - _temp_error(HOTEND_INDEX, PSTR(MSG_T_MINTEMP), PSTR(MSG_ERR_MINTEMP)); } float Temperature::get_pid_output(int e) { @@ -558,7 +554,6 @@ float Temperature::get_pid_output(int e) { } pTerm[HOTEND_INDEX] = PID_PARAM(Kp, HOTEND_INDEX) * pid_error[HOTEND_INDEX]; temp_iState[HOTEND_INDEX] += pid_error[HOTEND_INDEX]; - temp_iState[HOTEND_INDEX] = constrain(temp_iState[HOTEND_INDEX], temp_iState_min[HOTEND_INDEX], temp_iState_max[HOTEND_INDEX]); iTerm[HOTEND_INDEX] = PID_PARAM(Ki, HOTEND_INDEX) * temp_iState[HOTEND_INDEX]; pid_output = pTerm[HOTEND_INDEX] + iTerm[HOTEND_INDEX] - dTerm[HOTEND_INDEX]; @@ -621,7 +616,6 @@ float Temperature::get_pid_output(int e) { pid_error_bed = target_temperature_bed - current_temperature_bed; pTerm_bed = bedKp * pid_error_bed; temp_iState_bed += pid_error_bed; - temp_iState_bed = constrain(temp_iState_bed, temp_iState_min_bed, temp_iState_max_bed); iTerm_bed = bedKi * temp_iState_bed; dTerm_bed = K2 * bedKd * (current_temperature_bed - temp_dState_bed) + K1 * dTerm_bed; @@ -675,9 +669,8 @@ void Temperature::manage_heater() { updateTemperaturesFromRawValues(); // also resets the watchdog #if ENABLED(HEATER_0_USES_MAX6675) - float ct = current_temperature[0]; - if (ct > min(HEATER_0_MAXTEMP, 1023)) max_temp_error(0); - if (ct < max(HEATER_0_MINTEMP, 0.01)) min_temp_error(0); + if (current_temperature[0] > min(HEATER_0_MAXTEMP, MAX6675_TMAX - 1)) max_temp_error(0); + if (current_temperature[0] < max(HEATER_0_MINTEMP, MAX6675_TMIN + 0.01)) min_temp_error(0); #endif #if (ENABLED(THERMAL_PROTECTION_HOTENDS) && WATCH_TEMP_PERIOD > 0) || (ENABLED(THERMAL_PROTECTION_BED) && WATCH_BED_TEMP_PERIOD > 0) || DISABLED(PIDTEMPBED) || HAS_AUTO_FAN @@ -750,7 +743,7 @@ void Temperature::manage_heater() { // Control the extruder rate based on the width sensor #if ENABLED(FILAMENT_WIDTH_SENSOR) if (filament_sensor) { - meas_shift_index = filwidth_delay_index1 - meas_delay_cm; + meas_shift_index = filwidth_delay_index[0] - meas_delay_cm; if (meas_shift_index < 0) meas_shift_index += MAX_MEASUREMENT_DELAY + 1; //loop around buffer if needed // Get the delayed info and add 100 to reconstitute to a percent of @@ -950,16 +943,10 @@ void Temperature::init() { // populate with the first value maxttemp[e] = maxttemp[0]; #if ENABLED(PIDTEMP) - temp_iState_min[e] = 0.0; - temp_iState_max[e] = (PID_INTEGRAL_DRIVE_MAX) / PID_PARAM(Ki, e); #if ENABLED(PID_EXTRUSION_SCALING) last_e_position = 0; #endif #endif //PIDTEMP - #if ENABLED(PIDTEMPBED) - temp_iState_min_bed = 0.0; - temp_iState_max_bed = (PID_BED_INTEGRAL_DRIVE_MAX) / bedKi; - #endif //PIDTEMPBED } #if ENABLED(PIDTEMP) && ENABLED(PID_EXTRUSION_SCALING) @@ -982,49 +969,43 @@ void Temperature::init() { SET_OUTPUT(HEATER_BED_PIN); #endif - #if ENABLED(FAST_PWM_FAN) || ENABLED(FAN_SOFT_PWM) - - #if HAS_FAN0 - SET_OUTPUT(FAN_PIN); - #if ENABLED(FAST_PWM_FAN) - setPwmFrequency(FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8 - #endif - #if ENABLED(FAN_SOFT_PWM) - soft_pwm_fan[0] = fanSpeedSoftPwm[0] / 2; - #endif + #if HAS_FAN0 + SET_OUTPUT(FAN_PIN); + #if ENABLED(FAST_PWM_FAN) + setPwmFrequency(FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8 #endif - - #if HAS_FAN1 - SET_OUTPUT(FAN1_PIN); - #if ENABLED(FAST_PWM_FAN) - setPwmFrequency(FAN1_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8 - #endif - #if ENABLED(FAN_SOFT_PWM) - soft_pwm_fan[1] = fanSpeedSoftPwm[1] / 2; - #endif + #if ENABLED(FAN_SOFT_PWM) + soft_pwm_fan[0] = fanSpeedSoftPwm[0] >> 1; #endif + #endif - #if HAS_FAN2 - SET_OUTPUT(FAN2_PIN); - #if ENABLED(FAST_PWM_FAN) - setPwmFrequency(FAN2_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8 - #endif - #if ENABLED(FAN_SOFT_PWM) - soft_pwm_fan[2] = fanSpeedSoftPwm[2] / 2; - #endif + #if HAS_FAN1 + SET_OUTPUT(FAN1_PIN); + #if ENABLED(FAST_PWM_FAN) + setPwmFrequency(FAN1_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8 #endif + #if ENABLED(FAN_SOFT_PWM) + soft_pwm_fan[1] = fanSpeedSoftPwm[1] >> 1; + #endif + #endif - #endif // FAST_PWM_FAN || FAN_SOFT_PWM + #if HAS_FAN2 + SET_OUTPUT(FAN2_PIN); + #if ENABLED(FAST_PWM_FAN) + setPwmFrequency(FAN2_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8 + #endif + #if ENABLED(FAN_SOFT_PWM) + soft_pwm_fan[2] = fanSpeedSoftPwm[2] >> 1; + #endif + #endif #if ENABLED(HEATER_0_USES_MAX6675) - #if DISABLED(SDSUPPORT) - OUT_WRITE(SCK_PIN, LOW); - OUT_WRITE(MOSI_PIN, HIGH); - OUT_WRITE(MISO_PIN, HIGH); - #else - OUT_WRITE(SS_PIN, HIGH); - #endif + OUT_WRITE(SCK_PIN, LOW); + OUT_WRITE(MOSI_PIN, HIGH); + SET_INPUT(MISO_PIN); + WRITE(MISO_PIN, HIGH); + OUT_WRITE(SS_PIN, HIGH); OUT_WRITE(MAX6675_SS, HIGH); @@ -1062,16 +1043,44 @@ void Temperature::init() { #endif #if HAS_AUTO_FAN_0 - pinMode(EXTRUDER_0_AUTO_FAN_PIN, OUTPUT); + #if E0_AUTO_FAN_PIN == FAN1_PIN + SET_OUTPUT(E0_AUTO_FAN_PIN); + #if ENABLED(FAST_PWM_FAN) + setPwmFrequency(E0_AUTO_FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8 + #endif + #else + SET_OUTPUT(E0_AUTO_FAN_PIN); + #endif #endif - #if HAS_AUTO_FAN_1 && (EXTRUDER_1_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN) - pinMode(EXTRUDER_1_AUTO_FAN_PIN, OUTPUT); + #if HAS_AUTO_FAN_1 && !AUTO_1_IS_0 + #if E1_AUTO_FAN_PIN == FAN1_PIN + SET_OUTPUT(E1_AUTO_FAN_PIN); + #if ENABLED(FAST_PWM_FAN) + setPwmFrequency(E1_AUTO_FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8 + #endif + #else + SET_OUTPUT(E1_AUTO_FAN_PIN); + #endif #endif - #if HAS_AUTO_FAN_2 && (EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN) && (EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN) - pinMode(EXTRUDER_2_AUTO_FAN_PIN, OUTPUT); + #if HAS_AUTO_FAN_2 && !AUTO_2_IS_0 && !AUTO_2_IS_1 + #if E2_AUTO_FAN_PIN == FAN1_PIN + SET_OUTPUT(E2_AUTO_FAN_PIN); + #if ENABLED(FAST_PWM_FAN) + setPwmFrequency(E2_AUTO_FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8 + #endif + #else + SET_OUTPUT(E2_AUTO_FAN_PIN); + #endif #endif - #if HAS_AUTO_FAN_3 && (EXTRUDER_3_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN) && (EXTRUDER_3_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN) && (EXTRUDER_3_AUTO_FAN_PIN != EXTRUDER_2_AUTO_FAN_PIN) - pinMode(EXTRUDER_3_AUTO_FAN_PIN, OUTPUT); + #if HAS_AUTO_FAN_3 && !AUTO_3_IS_0 && !AUTO_3_IS_1 && !AUTO_3_IS_2 + #if E3_AUTO_FAN_PIN == FAN1_PIN + SET_OUTPUT(E3_AUTO_FAN_PIN); + #if ENABLED(FAST_PWM_FAN) + setPwmFrequency(E3_AUTO_FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8 + #endif + #else + SET_OUTPUT(E3_AUTO_FAN_PIN); + #endif #endif // Use timer0 for temperature measurement @@ -1229,12 +1238,12 @@ void Temperature::init() { *state = TRStable; // While the temperature is stable watch for a bad temperature case TRStable: - if (temperature < tr_target_temperature[heater_index] - hysteresis_degc && ELAPSED(millis(), *timer)) - *state = TRRunaway; - else { + if (temperature >= tr_target_temperature[heater_index] - hysteresis_degc) { *timer = millis() + period_seconds * 1000UL; break; } + else if (PENDING(millis(), *timer)) break; + *state = TRRunaway; case TRRunaway: _temp_error(heater_id, PSTR(MSG_T_THERMAL_RUNAWAY), PSTR(MSG_THERMAL_RUNAWAY)); } @@ -1256,9 +1265,7 @@ void Temperature::disable_all_heaters() { } #if HAS_TEMP_HOTEND - setTargetHotend(0, 0); - soft_pwm[0] = 0; - WRITE_HEATER_0P(LOW); // Should HEATERS_PARALLEL apply here? Then change to DISABLE_HEATER(0) + DISABLE_HEATER(0); #endif #if HOTENDS > 1 && HAS_TEMP_1 @@ -1334,10 +1341,28 @@ void Temperature::disable_all_heaters() { WRITE(MAX6675_SS, 1); // disable TT_MAX6675 - if (max6675_temp & MAX6675_ERROR_MASK) - max6675_temp = 4000; // thermocouple open + if (max6675_temp & MAX6675_ERROR_MASK) { + SERIAL_ERROR_START; + SERIAL_ERRORPGM("Temp measurement error! "); + #if MAX6675_ERROR_MASK == 7 + SERIAL_ERRORPGM("MAX31855 "); + if (max6675_temp & 1) + SERIAL_ERRORLNPGM("Open Circuit"); + else if (max6675_temp & 2) + SERIAL_ERRORLNPGM("Short to GND"); + else if (max6675_temp & 4) + SERIAL_ERRORLNPGM("Short to VCC"); + #else + SERIAL_ERRORLNPGM("MAX6675"); + #endif + max6675_temp = MAX6675_TMAX * 4; // thermocouple open + } else max6675_temp >>= MAX6675_DISCARD_BITS; + #if ENABLED(MAX6675_IS_MAX31855) + // Support negative temperature + if (max6675_temp & 0x00002000) max6675_temp |= 0xffffc000; + #endif return (int)max6675_temp; } @@ -1368,8 +1393,94 @@ void Temperature::set_current_temp_raw() { temp_meas_ready = true; } +#if ENABLED(PINS_DEBUGGING) + /** + * monitors endstops & Z probe for changes + * + * If a change is detected then the LED is toggled and + * a message is sent out the serial port + * + * Yes, we could miss a rapid back & forth change but + * that won't matter because this is all manual. + * + */ + void endstop_monitor() { + static uint16_t old_endstop_bits_local = 0; + static uint8_t local_LED_status = 0; + uint16_t current_endstop_bits_local = 0; + #if HAS_X_MIN + if (READ(X_MIN_PIN)) SBI(current_endstop_bits_local, X_MIN); + #endif + #if HAS_X_MAX + if (READ(X_MAX_PIN)) SBI(current_endstop_bits_local, X_MAX); + #endif + #if HAS_Y_MIN + if (READ(Y_MIN_PIN)) SBI(current_endstop_bits_local, Y_MIN); + #endif + #if HAS_Y_MAX + if (READ(Y_MAX_PIN)) SBI(current_endstop_bits_local, Y_MAX); + #endif + #if HAS_Z_MIN + if (READ(Z_MIN_PIN)) SBI(current_endstop_bits_local, Z_MIN); + #endif + #if HAS_Z_MAX + if (READ(Z_MAX_PIN)) SBI(current_endstop_bits_local, Z_MAX); + #endif + #if HAS_Z_MIN_PROBE_PIN + if (READ(Z_MIN_PROBE_PIN)) SBI(current_endstop_bits_local, Z_MIN_PROBE); + #endif + #if HAS_Z2_MIN + if (READ(Z2_MIN_PIN)) SBI(current_endstop_bits_local, Z2_MIN); + #endif + #if HAS_Z2_MAX + if (READ(Z2_MAX_PIN)) SBI(current_endstop_bits_local, Z2_MAX); + #endif + + uint16_t endstop_change = current_endstop_bits_local ^ old_endstop_bits_local; + + if (endstop_change) { + #if HAS_X_MIN + if (TEST(endstop_change, X_MIN)) SERIAL_PROTOCOLPAIR("X_MIN:", !!TEST(current_endstop_bits_local, X_MIN)); + #endif + #if HAS_X_MAX + if (TEST(endstop_change, X_MAX)) SERIAL_PROTOCOLPAIR(" X_MAX:", !!TEST(current_endstop_bits_local, X_MAX)); + #endif + #if HAS_Y_MIN + if (TEST(endstop_change, Y_MIN)) SERIAL_PROTOCOLPAIR(" Y_MIN:", !!TEST(current_endstop_bits_local, Y_MIN)); + #endif + #if HAS_Y_MAX + if (TEST(endstop_change, Y_MAX)) SERIAL_PROTOCOLPAIR(" Y_MAX:", !!TEST(current_endstop_bits_local, Y_MAX)); + #endif + #if HAS_Z_MIN + if (TEST(endstop_change, Z_MIN)) SERIAL_PROTOCOLPAIR(" Z_MIN:", !!TEST(current_endstop_bits_local, Z_MIN)); + #endif + #if HAS_Z_MAX + if (TEST(endstop_change, Z_MAX)) SERIAL_PROTOCOLPAIR(" Z_MAX:", !!TEST(current_endstop_bits_local, Z_MAX)); + #endif + #if HAS_Z_MIN_PROBE_PIN + if (TEST(endstop_change, Z_MIN_PROBE)) SERIAL_PROTOCOLPAIR(" PROBE:", !!TEST(current_endstop_bits_local, Z_MIN_PROBE)); + #endif + #if HAS_Z2_MIN + if (TEST(endstop_change, Z2_MIN)) SERIAL_PROTOCOLPAIR(" Z2_MIN:", !!TEST(current_endstop_bits_local, Z2_MIN)); + #endif + #if HAS_Z2_MAX + if (TEST(endstop_change, Z2_MAX)) SERIAL_PROTOCOLPAIR(" Z2_MAX:", !!TEST(current_endstop_bits_local, Z2_MAX)); + #endif + SERIAL_PROTOCOLPGM("\n\n"); + analogWrite(LED_PIN, local_LED_status); + local_LED_status ^= 255; + old_endstop_bits_local = current_endstop_bits_local; + } + } +#endif // PINS_DEBUGGING + /** - * Timer 0 is shared with millies + * Timer 0 is shared with millies so don't change the prescaler. + * + * This ISR uses the compare method so it runs at the base + * frequency (16 MHz / 64 / 256 = 976.5625 Hz), but at the TCNT0 set + * in OCR0B above (128 or halfway between OVFs). + * * - Manage PWM to all the heaters and fan * - Update the raw temperature values * - Check new temperature values for MIN/MAX errors @@ -1378,25 +1489,28 @@ void Temperature::set_current_temp_raw() { ISR(TIMER0_COMPB_vect) { Temperature::isr(); } void Temperature::isr() { + //Allow UART and stepper ISRs + CBI(TIMSK0, OCIE0B); //Disable Temperature ISR + sei(); - static unsigned char temp_count = 0; + static uint8_t temp_count = 0; static TempState temp_state = StartupDelay; - static unsigned char pwm_count = _BV(SOFT_PWM_SCALE); + static uint8_t pwm_count = _BV(SOFT_PWM_SCALE); // Static members for each heater #if ENABLED(SLOW_PWM_HEATERS) - static unsigned char slow_pwm_count = 0; + static uint8_t slow_pwm_count = 0; #define ISR_STATICS(n) \ - static unsigned char soft_pwm_ ## n; \ - static unsigned char state_heater_ ## n = 0; \ - static unsigned char state_timer_heater_ ## n = 0 + static uint8_t soft_pwm_ ## n; \ + static uint8_t state_heater_ ## n = 0; \ + static uint8_t state_timer_heater_ ## n = 0 #else - #define ISR_STATICS(n) static unsigned char soft_pwm_ ## n + #define ISR_STATICS(n) static uint8_t soft_pwm_ ## n #endif // Statics per heater ISR_STATICS(0); - #if (HOTENDS > 1) || ENABLED(HEATERS_PARALLEL) + #if HOTENDS > 1 ISR_STATICS(1); #if HOTENDS > 2 ISR_STATICS(2); @@ -1415,15 +1529,11 @@ void Temperature::isr() { #if DISABLED(SLOW_PWM_HEATERS) /** - * standard PWM modulation + * Standard PWM modulation */ if (pwm_count == 0) { soft_pwm_0 = soft_pwm[0]; - if (soft_pwm_0 > 0) { - WRITE_HEATER_0(1); - } - else WRITE_HEATER_0P(0); // If HEATERS_PARALLEL should apply, change to WRITE_HEATER_0 - + WRITE_HEATER_0(soft_pwm_0 > 0 ? 1 : 0); #if HOTENDS > 1 soft_pwm_1 = soft_pwm[1]; WRITE_HEATER_1(soft_pwm_1 > 0 ? 1 : 0); @@ -1444,15 +1554,15 @@ void Temperature::isr() { #if ENABLED(FAN_SOFT_PWM) #if HAS_FAN0 - soft_pwm_fan[0] = fanSpeedSoftPwm[0] / 2; + soft_pwm_fan[0] = fanSpeedSoftPwm[0] >> 1; WRITE_FAN(soft_pwm_fan[0] > 0 ? 1 : 0); #endif #if HAS_FAN1 - soft_pwm_fan[1] = fanSpeedSoftPwm[1] / 2; + soft_pwm_fan[1] = fanSpeedSoftPwm[1] >> 1; WRITE_FAN1(soft_pwm_fan[1] > 0 ? 1 : 0); #endif #if HAS_FAN2 - soft_pwm_fan[2] = fanSpeedSoftPwm[2] / 2; + soft_pwm_fan[2] = fanSpeedSoftPwm[2] >> 1; WRITE_FAN2(soft_pwm_fan[2] > 0 ? 1 : 0); #endif #endif @@ -1485,21 +1595,29 @@ void Temperature::isr() { #endif #endif + // SOFT_PWM_SCALE to frequency: + // + // 0: 16000000/64/256/128 = 7.6294 Hz + // 1: / 64 = 15.2588 Hz + // 2: / 32 = 30.5176 Hz + // 3: / 16 = 61.0352 Hz + // 4: / 8 = 122.0703 Hz + // 5: / 4 = 244.1406 Hz pwm_count += _BV(SOFT_PWM_SCALE); - pwm_count &= 0x7f; + pwm_count &= 0x7F; #else // SLOW_PWM_HEATERS /** * SLOW PWM HEATERS * - * for heaters drived by relay + * For relay-driven heaters */ #ifndef MIN_STATE_TIME #define MIN_STATE_TIME 16 // MIN_STATE_TIME * 65.5 = time in milliseconds #endif - // Macros for Slow PWM timer logic - HEATERS_PARALLEL applies + // Macros for Slow PWM timer logic #define _SLOW_PWM_ROUTINE(NR, src) \ soft_pwm_ ## NR = src; \ if (soft_pwm_ ## NR > 0) { \ @@ -1562,15 +1680,15 @@ void Temperature::isr() { #if ENABLED(FAN_SOFT_PWM) if (pwm_count == 0) { #if HAS_FAN0 - soft_pwm_fan[0] = fanSpeedSoftPwm[0] / 2; + soft_pwm_fan[0] = fanSpeedSoftPwm[0] >> 1; WRITE_FAN(soft_pwm_fan[0] > 0 ? 1 : 0); #endif #if HAS_FAN1 - soft_pwm_fan[1] = fanSpeedSoftPwm[1] / 2; + soft_pwm_fan[1] = fanSpeedSoftPwm[1] >> 1; WRITE_FAN1(soft_pwm_fan[1] > 0 ? 1 : 0); #endif #if HAS_FAN2 - soft_pwm_fan[2] = fanSpeedSoftPwm[2] / 2; + soft_pwm_fan[2] = fanSpeedSoftPwm[2] >> 1; WRITE_FAN2(soft_pwm_fan[2] > 0 ? 1 : 0); #endif } @@ -1585,10 +1703,18 @@ void Temperature::isr() { #endif #endif //FAN_SOFT_PWM + // SOFT_PWM_SCALE to frequency: + // + // 0: 16000000/64/256/128 = 7.6294 Hz + // 1: / 64 = 15.2588 Hz + // 2: / 32 = 30.5176 Hz + // 3: / 16 = 61.0352 Hz + // 4: / 8 = 122.0703 Hz + // 5: / 4 = 244.1406 Hz pwm_count += _BV(SOFT_PWM_SCALE); - pwm_count &= 0x7f; + pwm_count &= 0x7F; - // increment slow_pwm_count only every 64 pwm_count circa 65.5ms + // increment slow_pwm_count only every 64 pwm_count (e.g., every 8s) if ((pwm_count % 64) == 0) { slow_pwm_count++; slow_pwm_count &= 0x7f; @@ -1720,6 +1846,9 @@ void Temperature::isr() { } // switch(temp_state) if (temp_count >= OVERSAMPLENR) { // 10 * 16 * 1/(16000000/64/256) = 164ms. + + temp_count = 0; + // Update the raw values if they've been read. Else we could be updating them during reading. if (!temp_meas_ready) set_current_temp_raw(); @@ -1728,85 +1857,54 @@ void Temperature::isr() { current_raw_filwidth = raw_filwidth_value >> 10; // Divide to get to 0-16384 range since we used 1/128 IIR filter approach #endif - temp_count = 0; - for (int i = 0; i < 4; i++) raw_temp_value[i] = 0; + ZERO(raw_temp_value); raw_temp_bed_value = 0; - #if HAS_TEMP_0 && DISABLED(HEATER_0_USES_MAX6675) - #if HEATER_0_RAW_LO_TEMP > HEATER_0_RAW_HI_TEMP - #define GE0 <= + int constexpr temp_dir[] = { + #if ENABLED(HEATER_0_USES_MAX6675) + 0 + #elif HEATER_0_RAW_LO_TEMP > HEATER_0_RAW_HI_TEMP + -1 #else - #define GE0 >= + 1 #endif - if (current_temperature_raw[0] GE0 maxttemp_raw[0]) max_temp_error(0); - if (minttemp_raw[0] GE0 current_temperature_raw[0] && !is_preheating(0) && target_temperature[0] > 0.0f) { - #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED - if (++consecutive_low_temperature_error[0] >= MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED) + #if HAS_TEMP_1 && HOTENDS > 1 + #if HEATER_1_RAW_LO_TEMP > HEATER_1_RAW_HI_TEMP + , -1 + #else + , 1 #endif - min_temp_error(0); - } - #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED - else - consecutive_low_temperature_error[0] = 0; #endif - #endif + #if HAS_TEMP_2 && HOTENDS > 2 + #if HEATER_2_RAW_LO_TEMP > HEATER_2_RAW_HI_TEMP + , -1 + #else + , 1 + #endif + #endif + #if HAS_TEMP_3 && HOTENDS > 3 + #if HEATER_3_RAW_LO_TEMP > HEATER_3_RAW_HI_TEMP + , -1 + #else + , 1 + #endif + #endif + }; - #if HAS_TEMP_1 && HOTENDS > 1 - #if HEATER_1_RAW_LO_TEMP > HEATER_1_RAW_HI_TEMP - #define GE1 <= - #else - #define GE1 >= - #endif - if (current_temperature_raw[1] GE1 maxttemp_raw[1]) max_temp_error(1); - if (minttemp_raw[1] GE1 current_temperature_raw[1] && !is_preheating(1) && target_temperature[1] > 0.0f) { + for (uint8_t e = 0; e < COUNT(temp_dir); e++) { + const int tdir = temp_dir[e], rawtemp = current_temperature_raw[e] * tdir; + if (rawtemp > maxttemp_raw[e] * tdir && target_temperature[e] > 0.0f) max_temp_error(e); + if (rawtemp < minttemp_raw[e] * tdir && !is_preheating(e) && target_temperature[e] > 0.0f) { #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED - if (++consecutive_low_temperature_error[1] >= MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED) + if (++consecutive_low_temperature_error[e] >= MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED) #endif - min_temp_error(1); + min_temp_error(e); } #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED else - consecutive_low_temperature_error[1] = 0; + consecutive_low_temperature_error[e] = 0; #endif - #endif // TEMP_SENSOR_1 - - #if HAS_TEMP_2 && HOTENDS > 2 - #if HEATER_2_RAW_LO_TEMP > HEATER_2_RAW_HI_TEMP - #define GE2 <= - #else - #define GE2 >= - #endif - if (current_temperature_raw[2] GE2 maxttemp_raw[2]) max_temp_error(2); - if (minttemp_raw[2] GE2 current_temperature_raw[2] && !is_preheating(2) && target_temperature[2] > 0.0f) { - #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED - if (++consecutive_low_temperature_error[2] >= MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED) - #endif - min_temp_error(2); - } - #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED - else - consecutive_low_temperature_error[2] = 0; - #endif - #endif // TEMP_SENSOR_2 - - #if HAS_TEMP_3 && HOTENDS > 3 - #if HEATER_3_RAW_LO_TEMP > HEATER_3_RAW_HI_TEMP - #define GE3 <= - #else - #define GE3 >= - #endif - if (current_temperature_raw[3] GE3 maxttemp_raw[3]) max_temp_error(3); - if (minttemp_raw[3] GE3 current_temperature_raw[3] && !is_preheating(3) && target_temperature[3] > 0.0f) { - #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED - if (++consecutive_low_temperature_error[3] >= MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED) - #endif - min_temp_error(3); - } - #ifdef MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED - else - consecutive_low_temperature_error[3] = 0; - #endif - #endif // TEMP_SENSOR_3 + } #if HAS_TEMP_BED #if HEATER_BED_RAW_LO_TEMP > HEATER_BED_RAW_HI_TEMP @@ -1814,24 +1912,37 @@ void Temperature::isr() { #else #define GEBED >= #endif - if (current_temperature_bed_raw GEBED bed_maxttemp_raw) _temp_error(-1, PSTR(MSG_T_MAXTEMP), PSTR(MSG_ERR_MAXTEMP_BED)); - if (bed_minttemp_raw GEBED current_temperature_bed_raw) _temp_error(-1, PSTR(MSG_T_MINTEMP), PSTR(MSG_ERR_MINTEMP_BED)); + if (current_temperature_bed_raw GEBED bed_maxttemp_raw && target_temperature_bed > 0.0f) max_temp_error(-1); + if (bed_minttemp_raw GEBED current_temperature_bed_raw && target_temperature_bed > 0.0f) min_temp_error(-1); #endif } // temp_count >= OVERSAMPLENR #if ENABLED(BABYSTEPPING) - for (uint8_t axis = X_AXIS; axis <= Z_AXIS; axis++) { + LOOP_XYZ(axis) { int curTodo = babystepsTodo[axis]; //get rid of volatile for performance if (curTodo > 0) { - stepper.babystep(axis,/*fwd*/true); + stepper.babystep((AxisEnum)axis,/*fwd*/true); babystepsTodo[axis]--; //fewer to do next time } else if (curTodo < 0) { - stepper.babystep(axis,/*fwd*/false); + stepper.babystep((AxisEnum)axis,/*fwd*/false); babystepsTodo[axis]++; //fewer to do next time } } #endif //BABYSTEPPING + + #if ENABLED(PINS_DEBUGGING) + extern bool endstop_monitor_flag; + // run the endstop monitor at 15Hz + static uint8_t endstop_monitor_count = 16; // offset this check from the others + if (endstop_monitor_flag) { + endstop_monitor_count += _BV(1); // 15 Hz + endstop_monitor_count &= 0x7F; + if (!endstop_monitor_count) endstop_monitor(); // report changes in endstop status + } + #endif + + SBI(TIMSK0, OCIE0B); //re-enable Temperature ISR } diff --git a/Marlin/temperature.h b/Marlin/temperature.h index ffb47a59fe..a6b9874c6a 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -65,10 +65,10 @@ class Temperature { static float redundant_temperature; #endif - static unsigned char soft_pwm_bed; + static uint8_t soft_pwm_bed; #if ENABLED(FAN_SOFT_PWM) - static unsigned char fanSpeedSoftPwm[FAN_COUNT]; + static uint8_t fanSpeedSoftPwm[FAN_COUNT]; #endif #if ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED) @@ -121,7 +121,7 @@ class Temperature { static millis_t watch_bed_next_ms; #endif - #if ENABLED(PREVENT_DANGEROUS_EXTRUDE) + #if ENABLED(PREVENT_COLD_EXTRUSION) static bool allow_cold_extrude; static float extrude_min_temp; static bool tooColdToExtrude(uint8_t e) { @@ -157,9 +157,7 @@ class Temperature { static int lpq_ptr; #endif - static float pid_error[HOTENDS], - temp_iState_min[HOTENDS], - temp_iState_max[HOTENDS]; + static float pid_error[HOTENDS]; static bool pid_reset[HOTENDS]; #endif @@ -169,9 +167,7 @@ class Temperature { pTerm_bed, iTerm_bed, dTerm_bed, - pid_error_bed, - temp_iState_min_bed, - temp_iState_max_bed; + pid_error_bed; #else static millis_t next_bed_check_ms; #endif @@ -209,10 +205,10 @@ class Temperature { static millis_t next_auto_fan_check_ms; #endif - static unsigned char soft_pwm[HOTENDS]; + static uint8_t soft_pwm[HOTENDS]; #if ENABLED(FAN_SOFT_PWM) - static unsigned char soft_pwm_fan[FAN_COUNT]; + static uint8_t soft_pwm_fan[FAN_COUNT]; #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) @@ -376,20 +372,20 @@ class Temperature { */ static void updatePID(); - static void autotempShutdown() { - #if ENABLED(AUTOTEMP) + #if ENABLED(AUTOTEMP) + static void autotempShutdown() { if (planner.autotemp_enabled) { planner.autotemp_enabled = false; if (degTargetHotend(EXTRUDER_IDX) > planner.autotemp_min) setTargetHotend(0, EXTRUDER_IDX); } - #endif - } + } + #endif #if ENABLED(BABYSTEPPING) - static void babystep_axis(AxisEnum axis, int distance) { - #if ENABLED(COREXY) || ENABLED(COREXZ) || ENABLED(COREYZ) + static void babystep_axis(const AxisEnum axis, const int distance) { + #if IS_CORE #if ENABLED(BABYSTEP_XY) switch (axis) { case CORE_AXIS_1: // X on CoreXY and CoreXZ, Y on CoreYZ @@ -397,17 +393,17 @@ class Temperature { babystepsTodo[CORE_AXIS_2] += distance * 2; break; case CORE_AXIS_2: // Y on CoreXY, Z on CoreXZ and CoreYZ - babystepsTodo[CORE_AXIS_1] += distance * 2; - babystepsTodo[CORE_AXIS_2] -= distance * 2; + babystepsTodo[CORE_AXIS_1] += CORESIGN(distance * 2); + babystepsTodo[CORE_AXIS_2] -= CORESIGN(distance * 2); break; case NORMAL_AXIS: // Z on CoreXY, Y on CoreXZ, X on CoreYZ babystepsTodo[NORMAL_AXIS] += distance; break; } - #elif ENABLED(COREXZ) || ENABLED(COREYZ) + #elif CORE_IS_XZ || CORE_IS_YZ // Only Z stepping needs to be handled here - babystepsTodo[CORE_AXIS_1] += distance * 2; - babystepsTodo[CORE_AXIS_2] -= distance * 2; + babystepsTodo[CORE_AXIS_1] += CORESIGN(distance * 2); + babystepsTodo[CORE_AXIS_2] -= CORESIGN(distance * 2); #else babystepsTodo[Z_AXIS] += distance; #endif @@ -437,8 +433,8 @@ class Temperature { #endif static void _temp_error(int e, const char* serial_msg, const char* lcd_msg); - static void min_temp_error(uint8_t e); - static void max_temp_error(uint8_t e); + static void min_temp_error(int8_t e); + static void max_temp_error(int8_t e); #if ENABLED(THERMAL_PROTECTION_HOTENDS) || HAS_THERMALLY_PROTECTED_BED diff --git a/Marlin/twibus.cpp b/Marlin/twibus.cpp index c1d6008ddd..c5abdb2a9a 100644 --- a/Marlin/twibus.cpp +++ b/Marlin/twibus.cpp @@ -25,92 +25,178 @@ #if ENABLED(EXPERIMENTAL_I2CBUS) #include "twibus.h" - #include TWIBus::TWIBus() { - Wire.begin(); // We use no address so we will join the BUS as the master + #if I2C_SLAVE_ADDRESS == 0 + Wire.begin(); // No address joins the BUS as the master + #else + Wire.begin(I2C_SLAVE_ADDRESS); // Join the bus as a slave + #endif this->reset(); } void TWIBus::reset() { - this->addr = 0; this->buffer_s = 0; this->buffer[0] = 0x00; } -void TWIBus::address(uint8_t addr) { - this->addr = addr; +void TWIBus::address(const uint8_t adr) { + if (adr < 8 || adr > 127) { + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM("Bad I2C address (8-127)"); + } + + this->addr = adr; #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("sendto"), this->addr); + debug(PSTR("address"), adr); #endif } -void TWIBus::addbyte(char c) { - if (buffer_s >= sizeof(this->buffer)) return; +void TWIBus::addbyte(const char c) { + if (this->buffer_s >= COUNT(this->buffer)) return; this->buffer[this->buffer_s++] = c; - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("addbyte"), this->buffer[this->buffer_s - 1]); + debug(PSTR("addbyte"), c); #endif } +void TWIBus::addbytes(char src[], uint8_t bytes) { + #if ENABLED(DEBUG_TWIBUS) + debug(PSTR("addbytes"), bytes); + #endif + while (bytes--) this->addbyte(*src++); +} + +void TWIBus::addstring(char str[]) { + #if ENABLED(DEBUG_TWIBUS) + debug(PSTR("addstring"), str); + #endif + while (char c = *str++) this->addbyte(c); +} + void TWIBus::send() { - if (!this->addr) return; - #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("send()")); + debug(PSTR("send"), this->addr); #endif Wire.beginTransmission(this->addr); Wire.write(this->buffer, this->buffer_s); Wire.endTransmission(); - // Reset the buffer after sending the data this->reset(); } -void TWIBus::reqbytes(uint8_t bytes) { - if (!this->addr) return; +// static +void TWIBus::echoprefix(uint8_t bytes, const char prefix[], uint8_t adr) { + SERIAL_ECHO_START; + serialprintPGM(prefix); + SERIAL_ECHOPAIR(": from:", adr); + SERIAL_ECHOPAIR(" bytes:", bytes); + SERIAL_ECHOPGM (" data:"); +} + +// static +void TWIBus::echodata(uint8_t bytes, const char prefix[], uint8_t adr) { + echoprefix(bytes, prefix, adr); + while (bytes-- && Wire.available()) SERIAL_CHAR(Wire.read()); + SERIAL_EOL; +} + +void TWIBus::echobuffer(const char prefix[], uint8_t adr) { + echoprefix(this->buffer_s, prefix, adr); + for (uint8_t i = 0; i < this->buffer_s; i++) SERIAL_CHAR(this->buffer[i]); + SERIAL_EOL; +} + +bool TWIBus::request(const uint8_t bytes) { + if (!this->addr) return false; #if ENABLED(DEBUG_TWIBUS) - debug(PSTR("reqbytes"), bytes); + debug(PSTR("request"), bytes); #endif - millis_t t = millis() + this->timeout; - Wire.requestFrom(this->addr, bytes); - - // requestFrom() is a blocking function - while (Wire.available() < bytes) { - if (ELAPSED(millis(), t)) break; - else continue; + // requestFrom() is a blocking function + if (Wire.requestFrom(this->addr, bytes) == 0) { + #if ENABLED(DEBUG_TWIBUS) + debug("request fail", this->addr); + #endif + return false; } - SERIAL_ECHO_START; - SERIAL_ECHOPAIR("i2c-reply: from:", this->addr); - SERIAL_ECHOPAIR(" bytes:", Wire.available()); - SERIAL_ECHOPGM (" data:"); - - // Protect against buffer overflows if the number of received bytes - // is less than the number of requested bytes - uint8_t wba = Wire.available(); - for (int i = 0; i < wba; i++) SERIAL_CHAR(Wire.read()); - SERIAL_EOL; - - // Reset the buffer after sending the data - this->reset(); + return true; } +void TWIBus::relay(const uint8_t bytes) { + #if ENABLED(DEBUG_TWIBUS) + debug(PSTR("relay"), bytes); + #endif + + if (this->request(bytes)) + echodata(bytes, PSTR("i2c-reply"), this->addr); +} + +uint8_t TWIBus::capture(char *dst, const uint8_t bytes) { + this->reset(); + uint8_t count = 0; + while (count < bytes && Wire.available()) + dst[count++] = Wire.read(); + + #if ENABLED(DEBUG_TWIBUS) + debug(PSTR("capture"), count); + #endif + + return count; +} + +// static +void TWIBus::flush() { + while (Wire.available()) Wire.read(); +} + +#if I2C_SLAVE_ADDRESS > 0 + + void TWIBus::receive(uint8_t bytes) { + #if ENABLED(DEBUG_TWIBUS) + debug(PSTR("receive"), bytes); + #endif + echodata(bytes, PSTR("i2c-receive"), 0); + } + + void TWIBus::reply(char str[]/*=NULL*/) { + #if ENABLED(DEBUG_TWIBUS) + debug(PSTR("reply"), str); + #endif + + if (str) { + this->reset(); + this->addstring(str); + } + + Wire.write(this->buffer, this->buffer_s); + + this->reset(); + } + +#endif + #if ENABLED(DEBUG_TWIBUS) - void TWIBus::debug(const char func[], int32_t val/*=-1*/) { - if (DEBUGGING(INFO)) { - SERIAL_ECHOPGM("TWIBus::"); - serialprintPGM(func); - if (val >= 0) SERIAL_ECHOPAIR(": ", val); - SERIAL_EOL; - } + // static + void TWIBus::prefix(const char func[]) { + SERIAL_ECHOPGM("TWIBus::"); + serialprintPGM(func); + SERIAL_ECHOPGM(": "); + } + void TWIBus::debug(const char func[], uint32_t adr) { + if (DEBUGGING(INFO)) { prefix(func); SERIAL_ECHOLN(adr); } + } + void TWIBus::debug(const char func[], char c) { + if (DEBUGGING(INFO)) { prefix(func); SERIAL_ECHOLN(c); } + } + void TWIBus::debug(const char func[], char str[]) { + if (DEBUGGING(INFO)) { prefix(func); SERIAL_ECHOLN(str); } } #endif diff --git a/Marlin/twibus.h b/Marlin/twibus.h index d0d0e0ff32..dd1cc12673 100644 --- a/Marlin/twibus.h +++ b/Marlin/twibus.h @@ -25,9 +25,16 @@ #include "macros.h" +#include + // Print debug messages with M111 S2 (Uses 236 bytes of PROGMEM) //#define DEBUG_TWIBUS +typedef void (*twiReceiveFunc_t)(int bytes); +typedef void (*twiRequestFunc_t)(); + +#define TWIBUS_BUFFER_SIZE 32 + /** * TWIBUS class * @@ -36,92 +43,186 @@ * an experimental feature and it's inner workings as well as public facing * interface are prune to change in the future. * - * The two main consumers of this class are M155 and M156, where M155 allows + * The two main consumers of this class are M260 and M261, where M260 allows * Marlin to send a I2C packet to a device (please be aware that no repeated * starts are possible), this can be done in caching method by calling multiple - * times M155 B or a one liner M155, have a look at - * the gcode_M155() function for more information. M156 allows Marlin to + * times M260 B or a one liner M260, have a look at + * the gcode_M260() function for more information. M261 allows Marlin to * request data from a device, the received data is then relayed into the serial * line for host interpretation. * */ class TWIBus { private: - /** - * @brief Timeout value in milliseconds - * @details For blocking operations this constant value will set the max - * amount of time Marlin will keep waiting for a reply. Useful is something - * goes wrong on the bus and the SDA/SCL lines are held up by another device. - */ - const int timeout = 5; - - /** - * @brief Target device address - * @description This stores, until the buffer is flushed, the target device - * address, take not we do follow Arduino 7bit addressing. - */ - uint8_t addr = 0; - /** * @brief Number of bytes on buffer - * @description This var holds the total number of bytes on our buffer - * waiting to be flushed to the bus. + * @description Number of bytes in the buffer waiting to be flushed to the bus */ uint8_t buffer_s = 0; /** * @brief Internal buffer - * @details This is a fixed buffer, TWI command cannot be longer than this + * @details A fixed buffer. TWI commands can be no longer than this. */ - char buffer[30]; + char buffer[TWIBUS_BUFFER_SIZE]; public: + /** + * @brief Target device address + * @description The target device address. Persists until changed. + */ + uint8_t addr = 0; + /** * @brief Class constructor - * @details Initialized the TWI bus and clears the buffer + * @details Initialize the TWI bus and clear the buffer */ TWIBus(); /** * @brief Reset the buffer - * @details Brings the internal buffer to a known-empty state + * @details Set the buffer to a known-empty state */ void reset(); /** * @brief Send the buffer data to the bus - * @details Flushed the buffer into the bus targeting the cached slave device - * address. + * @details Flush the buffer to the target address */ void send(); /** * @brief Add one byte to the buffer - * @details Adds the byte to the buffer in a sequential way, if buffer is full - * the request is silently ignored. + * @details Add a byte to the end of the buffer. + * Silently fails if the buffer is full. * * @param c a data byte */ - void addbyte(char c); + void addbyte(const char c); /** - * @brief Sets the target slave address - * @details The target slave address is stored so it can be later used when - * the complete packet needs to be sent over the bus. + * @brief Add some bytes to the buffer + * @details Add bytes to the end of the buffer. + * Concatenates at the buffer size. * - * @param addr 7-bit integer address + * @param src source data address + * @param bytes the number of bytes to add */ - void address(uint8_t addr); + void addbytes(char src[], uint8_t bytes); /** - * @brief Request data from slave device - * @details Requests data from a slave device, when the data is received it will - * be relayed to the serial line using a parser-friendly formatting. + * @brief Add a null-terminated string to the buffer + * @details Add bytes to the end of the buffer up to a nul. + * Concatenates at the buffer size. + * + * @param str source string address + */ + void addstring(char str[]); + + /** + * @brief Set the target slave address + * @details The target slave address for sending the full packet + * + * @param adr 7-bit integer address + */ + void address(const uint8_t adr); + + /** + * @brief Prefix for echo to serial + * @details Echo a label, length, address, and "data:" * * @param bytes the number of bytes to request */ - void reqbytes(uint8_t bytes); + static void echoprefix(uint8_t bytes, const char prefix[], uint8_t adr); + + /** + * @brief Echo data on the bus to serial + * @details Echo some number of bytes from the bus + * to serial in a parser-friendly format. + * + * @param bytes the number of bytes to request + */ + static void echodata(uint8_t bytes, const char prefix[], uint8_t adr); + + /** + * @brief Echo data in the buffer to serial + * @details Echo the entire buffer to serial + * to serial in a parser-friendly format. + * + * @param bytes the number of bytes to request + */ + void echobuffer(const char prefix[], uint8_t adr); + + /** + * @brief Request data from the slave device and wait. + * @details Request a number of bytes from a slave device. + * Wait for the data to arrive, and return true + * on success. + * + * @param bytes the number of bytes to request + * @return status of the request: true=success, false=fail + */ + bool request(const uint8_t bytes); + + /** + * @brief Capture data from the bus into the buffer. + * @details Capture data after a request has succeeded. + * + * @param bytes the number of bytes to request + * @return the number of bytes captured to the buffer + */ + uint8_t capture(char *dst, const uint8_t bytes); + + /** + * @brief Flush the i2c bus. + * @details Get all bytes on the bus and throw them away. + */ + static void flush(); + + /** + * @brief Request data from the slave device, echo to serial. + * @details Request a number of bytes from a slave device and output + * the returned data to serial in a parser-friendly format. + * + * @param bytes the number of bytes to request + */ + void relay(const uint8_t bytes); + + #if I2C_SLAVE_ADDRESS > 0 + + /** + * @brief Register a slave receive handler + * @details Set a handler to receive data addressed to us + * + * @param handler A function to handle receiving bytes + */ + inline void onReceive(const twiReceiveFunc_t handler) { Wire.onReceive(handler); } + + /** + * @brief Register a slave request handler + * @details Set a handler to send data requested from us + * + * @param handler A function to handle receiving bytes + */ + inline void onRequest(const twiRequestFunc_t handler) { Wire.onRequest(handler); } + + /** + * @brief Default handler to receive + * @details Receive bytes sent to our slave address + * and simply echo them to serial. + */ + void receive(uint8_t bytes); + + /** + * @brief Send a reply to the bus + * @details Send the buffer and clear it. + * If a string is passed, write it into the buffer first. + */ + void reply(char str[]=NULL); + inline void reply(const char str[]) { this->reply((char*)str); } + + #endif #if ENABLED(DEBUG_TWIBUS) @@ -129,7 +230,11 @@ class TWIBus { * @brief Prints a debug message * @details Prints a simple debug message "TWIBus::function: value" */ - static void debug(const char func[], int32_t val = -1); + static void prefix(const char func[]); + static void debug(const char func[], uint32_t adr); + static void debug(const char func[], char c); + static void debug(const char func[], char adr[]); + static inline void debug(const char func[], uint8_t v) { debug(func, (uint32_t)v); } #endif }; diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index da214aa839..2aa5055b66 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -28,14 +28,22 @@ #include "temperature.h" #include "stepper.h" #include "configuration_store.h" +#include "utility.h" + +#if HAS_BUZZER && DISABLED(LCD_USE_I2C_BUZZER) + #include "buzzer.h" +#endif + +#if ENABLED(BLTOUCH) + #include "endstops.h" +#endif #if ENABLED(PRINTCOUNTER) #include "printcounter.h" #include "duration_t.h" #endif -int preheatHotendTemp1, preheatBedTemp1, preheatFanSpeed1, - preheatHotendTemp2, preheatBedTemp2, preheatFanSpeed2; +int lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2]; #if ENABLED(FILAMENT_LCD_DISPLAY) millis_t previous_lcd_status_ms = 0; @@ -51,12 +59,17 @@ char lcd_status_message[3 * (LCD_WIDTH) + 1] = WELCOME_MSG; // worst case is kan #endif // The main status screen -static void lcd_status_screen(); +void lcd_status_screen(); millis_t next_lcd_update_ms; uint8_t lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; // Set when the LCD needs to draw, decrements after every draw. Set to 2 in LCD routines so the LCD gets at least 1 full redraw (first redraw is partial) +#if ENABLED(DAC_STEPPER_CURRENT) + #include "stepper_dac.h" //was dac_mcp4728.h MarlinMain uses stepper dac for the m-codes + uint16_t driverPercent[XYZE]; +#endif + #if ENABLED(ULTIPANEL) // place-holders for Ki and Kd edits @@ -97,47 +110,55 @@ uint8_t lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; // Set when the LCD needs to #if HAS_POWER_SWITCH extern bool powersupply; #endif + const float manual_feedrate_mm_m[] = MANUAL_FEEDRATE; - static void lcd_main_menu(); - static void lcd_tune_menu(); - static void lcd_prepare_menu(); - static void lcd_move_menu(); - static void lcd_control_menu(); - static void lcd_control_temperature_menu(); - static void lcd_control_temperature_preheat_pla_settings_menu(); - static void lcd_control_temperature_preheat_abs_settings_menu(); - static void lcd_control_motion_menu(); - static void lcd_control_volumetric_menu(); + void lcd_main_menu(); + void lcd_tune_menu(); + void lcd_prepare_menu(); + void lcd_move_menu(); + void lcd_control_menu(); + void lcd_control_temperature_menu(); + void lcd_control_temperature_preheat_material1_settings_menu(); + void lcd_control_temperature_preheat_material2_settings_menu(); + void lcd_control_motion_menu(); + void lcd_control_volumetric_menu(); + + #if ENABLED(DAC_STEPPER_CURRENT) + void dac_driver_commit(); + void dac_driver_getValues(); + void lcd_dac_menu(); + void lcd_dac_write_eeprom(); + #endif #if ENABLED(LCD_INFO_MENU) #if ENABLED(PRINTCOUNTER) - static void lcd_info_stats_menu(); + void lcd_info_stats_menu(); #endif - static void lcd_info_thermistors_menu(); - static void lcd_info_board_menu(); - static void lcd_info_menu(); + void lcd_info_thermistors_menu(); + void lcd_info_board_menu(); + void lcd_info_menu(); #endif // LCD_INFO_MENU #if ENABLED(FILAMENT_CHANGE_FEATURE) - static void lcd_filament_change_option_menu(); - static void lcd_filament_change_init_message(); - static void lcd_filament_change_unload_message(); - static void lcd_filament_change_insert_message(); - static void lcd_filament_change_load_message(); - static void lcd_filament_change_extrude_message(); - static void lcd_filament_change_resume_message(); + void lcd_filament_change_option_menu(); + void lcd_filament_change_init_message(); + void lcd_filament_change_unload_message(); + void lcd_filament_change_insert_message(); + void lcd_filament_change_load_message(); + void lcd_filament_change_extrude_message(); + void lcd_filament_change_resume_message(); #endif #if HAS_LCD_CONTRAST - static void lcd_set_contrast(); + void lcd_set_contrast(); #endif #if ENABLED(FWRETRACT) - static void lcd_control_retract_menu(); + void lcd_control_retract_menu(); #endif #if ENABLED(DELTA_CALIBRATION_MENU) - static void lcd_delta_calibrate_menu(); + void lcd_delta_calibrate_menu(); #endif #if ENABLED(MANUAL_BED_LEVELING) @@ -148,33 +169,36 @@ uint8_t lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; // Set when the LCD needs to typedef void (*screenFunc_t)(); // Different types of actions that can be used in menu items. - static void menu_action_back(); - static void menu_action_submenu(screenFunc_t data); - static void menu_action_gcode(const char* pgcode); - static void menu_action_function(screenFunc_t data); - static void menu_action_setting_edit_bool(const char* pstr, bool* ptr); - static void menu_action_setting_edit_int3(const char* pstr, int* ptr, int minValue, int maxValue); - static void menu_action_setting_edit_float3(const char* pstr, float* ptr, float minValue, float maxValue); - static void menu_action_setting_edit_float32(const char* pstr, float* ptr, float minValue, float maxValue); - static void menu_action_setting_edit_float43(const char* pstr, float* ptr, float minValue, float maxValue); - static void menu_action_setting_edit_float5(const char* pstr, float* ptr, float minValue, float maxValue); - static void menu_action_setting_edit_float51(const char* pstr, float* ptr, float minValue, float maxValue); - static void menu_action_setting_edit_float52(const char* pstr, float* ptr, float minValue, float maxValue); - static void menu_action_setting_edit_long5(const char* pstr, unsigned long* ptr, unsigned long minValue, unsigned long maxValue); - static void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr, screenFunc_t callbackFunc); - static void menu_action_setting_edit_callback_int3(const char* pstr, int* ptr, int minValue, int maxValue, screenFunc_t callbackFunc); - static void menu_action_setting_edit_callback_float3(const char* pstr, float* ptr, float minValue, float maxValue, screenFunc_t callbackFunc); - static void menu_action_setting_edit_callback_float32(const char* pstr, float* ptr, float minValue, float maxValue, screenFunc_t callbackFunc); - static void menu_action_setting_edit_callback_float43(const char* pstr, float* ptr, float minValue, float maxValue, screenFunc_t callbackFunc); - static void menu_action_setting_edit_callback_float5(const char* pstr, float* ptr, float minValue, float maxValue, screenFunc_t callbackFunc); - static void menu_action_setting_edit_callback_float51(const char* pstr, float* ptr, float minValue, float maxValue, screenFunc_t callbackFunc); - static void menu_action_setting_edit_callback_float52(const char* pstr, float* ptr, float minValue, float maxValue, screenFunc_t callbackFunc); - static void menu_action_setting_edit_callback_long5(const char* pstr, unsigned long* ptr, unsigned long minValue, unsigned long maxValue, screenFunc_t callbackFunc); + #define menu_action_back(dummy) _menu_action_back() + void _menu_action_back(); + void menu_action_submenu(screenFunc_t data); + void menu_action_gcode(const char* pgcode); + void menu_action_function(screenFunc_t data); + void menu_action_setting_edit_bool(const char* pstr, bool* ptr); + void menu_action_setting_edit_int3(const char* pstr, int* ptr, int minValue, int maxValue); + void menu_action_setting_edit_float3(const char* pstr, float* ptr, float minValue, float maxValue); + void menu_action_setting_edit_float32(const char* pstr, float* ptr, float minValue, float maxValue); + void menu_action_setting_edit_float43(const char* pstr, float* ptr, float minValue, float maxValue); + void menu_action_setting_edit_float5(const char* pstr, float* ptr, float minValue, float maxValue); + void menu_action_setting_edit_float51(const char* pstr, float* ptr, float minValue, float maxValue); + void menu_action_setting_edit_float52(const char* pstr, float* ptr, float minValue, float maxValue); + void menu_action_setting_edit_float62(const char* pstr, float* ptr, float minValue, float maxValue); + void menu_action_setting_edit_long5(const char* pstr, unsigned long* ptr, unsigned long minValue, unsigned long maxValue); + void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr, screenFunc_t callbackFunc); + void menu_action_setting_edit_callback_int3(const char* pstr, int* ptr, int minValue, int maxValue, screenFunc_t callbackFunc); + void menu_action_setting_edit_callback_float3(const char* pstr, float* ptr, float minValue, float maxValue, screenFunc_t callbackFunc); + void menu_action_setting_edit_callback_float32(const char* pstr, float* ptr, float minValue, float maxValue, screenFunc_t callbackFunc); + void menu_action_setting_edit_callback_float43(const char* pstr, float* ptr, float minValue, float maxValue, screenFunc_t callbackFunc); + void menu_action_setting_edit_callback_float5(const char* pstr, float* ptr, float minValue, float maxValue, screenFunc_t callbackFunc); + void menu_action_setting_edit_callback_float51(const char* pstr, float* ptr, float minValue, float maxValue, screenFunc_t callbackFunc); + void menu_action_setting_edit_callback_float52(const char* pstr, float* ptr, float minValue, float maxValue, screenFunc_t callbackFunc); + void menu_action_setting_edit_callback_float62(const char* pstr, float* ptr, float minValue, float maxValue, screenFunc_t callbackFunc); + void menu_action_setting_edit_callback_long5(const char* pstr, unsigned long* ptr, unsigned long minValue, unsigned long maxValue, screenFunc_t callbackFunc); #if ENABLED(SDSUPPORT) - static void lcd_sdcard_menu(); - static void menu_action_sdfile(const char* filename, char* longFilename); - static void menu_action_sddirectory(const char* filename, char* longFilename); + void lcd_sdcard_menu(); + void menu_action_sdfile(const char* filename, char* longFilename); + void menu_action_sddirectory(const char* filename, char* longFilename); #endif /* Helper macros for menus */ @@ -189,6 +213,10 @@ uint8_t lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; // Set when the LCD needs to #define ENCODER_PULSES_PER_STEP 1 #endif + #ifndef TALL_FONT_CORRECTION + #define TALL_FONT_CORRECTION 0 + #endif + /** * START_SCREEN_OR_MENU generates init code for a screen or menu * @@ -206,13 +234,13 @@ uint8_t lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; // Set when the LCD needs to static int8_t _countedItems = 0; \ int8_t encoderLine = encoderPosition / ENCODER_STEPS_PER_MENU_ITEM; \ if (_countedItems > 0 && encoderLine >= _countedItems - LIMIT) { \ - encoderLine = _countedItems - LIMIT; \ + encoderLine = max(0, _countedItems - LIMIT); \ encoderPosition = encoderLine * (ENCODER_STEPS_PER_MENU_ITEM); \ } #define SCREEN_OR_MENU_LOOP() \ int8_t _menuLineNr = encoderTopLine, _thisItemNr; \ - for (int8_t _lcdLineNr = 0; _lcdLineNr < LCD_HEIGHT; _lcdLineNr++, _menuLineNr++) { \ + for (int8_t _lcdLineNr = 0; _lcdLineNr < LCD_HEIGHT - TALL_FONT_CORRECTION; _lcdLineNr++, _menuLineNr++) { \ _thisItemNr = 0 /** @@ -221,21 +249,20 @@ uint8_t lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; // Set when the LCD needs to * * START_MENU Opening code for a screen with menu items. * Scroll as-needed to keep the selected line in view. - * 'wasClicked' indicates the controller was clicked. */ #define START_SCREEN() \ - START_SCREEN_OR_MENU(LCD_HEIGHT); \ + START_SCREEN_OR_MENU(LCD_HEIGHT - TALL_FONT_CORRECTION); \ encoderTopLine = encoderLine; \ bool _skipStatic = false; \ SCREEN_OR_MENU_LOOP() #define START_MENU() \ START_SCREEN_OR_MENU(1); \ + screen_changed = false; \ NOMORE(encoderTopLine, encoderLine); \ - if (encoderLine >= encoderTopLine + LCD_HEIGHT) { \ - encoderTopLine = encoderLine - (LCD_HEIGHT - 1); \ + if (encoderLine >= encoderTopLine + LCD_HEIGHT - TALL_FONT_CORRECTION) { \ + encoderTopLine = encoderLine - (LCD_HEIGHT - TALL_FONT_CORRECTION - 1); \ } \ - bool wasClicked = LCD_CLICKED; \ bool _skipStatic = true; \ SCREEN_OR_MENU_LOOP() @@ -246,7 +273,9 @@ uint8_t lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; // Set when the LCD needs to * menu_action_[type](arg3...) * * Examples: - * MENU_ITEM(back, MSG_WATCH) + * MENU_ITEM(back, MSG_WATCH, 0 [dummy parameter] ) + * or + * MENU_BACK(MSG_WATCH) * lcd_implementation_drawmenu_back(sel, row, PSTR(MSG_WATCH)) * menu_action_back() * @@ -260,35 +289,36 @@ uint8_t lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; // Set when the LCD needs to * menu_action_setting_edit_int3(PSTR(MSG_SPEED), &feedrate_percentage, 10, 999) * */ - #define _MENU_ITEM_PART_1(TYPE, LABEL, ARGS...) \ + #define _MENU_ITEM_PART_1(TYPE, LABEL, ...) \ if (_menuLineNr == _thisItemNr) { \ if (lcdDrawUpdate) \ - lcd_implementation_drawmenu_ ## TYPE(encoderLine == _thisItemNr, _lcdLineNr, PSTR(LABEL), ## ARGS); \ - if (wasClicked && encoderLine == _thisItemNr) { \ - lcd_quick_feedback() + lcd_implementation_drawmenu_ ## TYPE(encoderLine == _thisItemNr, _lcdLineNr, PSTR(LABEL), ## __VA_ARGS__); \ + if (lcd_clicked && encoderLine == _thisItemNr) { - #define _MENU_ITEM_PART_2(TYPE, ARGS...) \ - menu_action_ ## TYPE(ARGS); \ - return; \ + #define _MENU_ITEM_PART_2(TYPE, ...) \ + menu_action_ ## TYPE(__VA_ARGS__); \ + if (screen_changed) return; \ } \ } \ ++_thisItemNr - #define MENU_ITEM(TYPE, LABEL, ARGS...) do { \ + #define MENU_ITEM(TYPE, LABEL, ...) do { \ _skipStatic = false; \ - _MENU_ITEM_PART_1(TYPE, LABEL, ## ARGS); \ - _MENU_ITEM_PART_2(TYPE, ## ARGS); \ + _MENU_ITEM_PART_1(TYPE, LABEL, ## __VA_ARGS__); \ + _MENU_ITEM_PART_2(TYPE, ## __VA_ARGS__); \ } while(0) + #define MENU_BACK(LABEL) MENU_ITEM(back, LABEL, 0) + // Used to print static text with no visible cursor. - #define STATIC_ITEM(LABEL, ARGS...) \ + #define STATIC_ITEM(LABEL, ...) \ if (_menuLineNr == _thisItemNr) { \ if (_skipStatic && encoderLine <= _thisItemNr) { \ encoderPosition += ENCODER_STEPS_PER_MENU_ITEM; \ lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; \ } \ if (lcdDrawUpdate) \ - lcd_implementation_drawmenu_static(_lcdLineNr, PSTR(LABEL), ## ARGS); \ + lcd_implementation_drawmenu_static(_lcdLineNr, PSTR(LABEL), ## __VA_ARGS__); \ } \ ++_thisItemNr @@ -308,24 +338,24 @@ uint8_t lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; // Set when the LCD needs to /** * MENU_MULTIPLIER_ITEM generates drawing and handling code for a multiplier menu item */ - #define MENU_MULTIPLIER_ITEM(type, label, args...) do { \ - _MENU_ITEM_PART_1(type, label, ## args); \ + #define MENU_MULTIPLIER_ITEM(type, label, ...) do { \ + _MENU_ITEM_PART_1(type, label, ## __VA_ARGS__); \ encoderRateMultiplierEnabled = true; \ lastEncoderMovementMillis = 0; \ - _MENU_ITEM_PART_2(type, ## args); \ + _MENU_ITEM_PART_2(type, ## __VA_ARGS__); \ } while(0) #endif //ENCODER_RATE_MULTIPLIER #define MENU_ITEM_DUMMY() do { _thisItemNr++; } while(0) - #define MENU_ITEM_EDIT(type, label, args...) MENU_ITEM(setting_edit_ ## type, label, PSTR(label), ## args) - #define MENU_ITEM_EDIT_CALLBACK(type, label, args...) MENU_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## args) + #define MENU_ITEM_EDIT(type, label, ...) MENU_ITEM(setting_edit_ ## type, label, PSTR(label), ## __VA_ARGS__) + #define MENU_ITEM_EDIT_CALLBACK(type, label, ...) MENU_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## __VA_ARGS__) #if ENABLED(ENCODER_RATE_MULTIPLIER) - #define MENU_MULTIPLIER_ITEM_EDIT(type, label, args...) MENU_MULTIPLIER_ITEM(setting_edit_ ## type, label, PSTR(label), ## args) - #define MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(type, label, args...) MENU_MULTIPLIER_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## args) + #define MENU_MULTIPLIER_ITEM_EDIT(type, label, ...) MENU_MULTIPLIER_ITEM(setting_edit_ ## type, label, PSTR(label), ## __VA_ARGS__) + #define MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(type, label, ...) MENU_MULTIPLIER_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## __VA_ARGS__) #else //!ENCODER_RATE_MULTIPLIER - #define MENU_MULTIPLIER_ITEM_EDIT(type, label, args...) MENU_ITEM(setting_edit_ ## type, label, PSTR(label), ## args) - #define MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(type, label, args...) MENU_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## args) + #define MENU_MULTIPLIER_ITEM_EDIT(type, label, ...) MENU_ITEM(setting_edit_ ## type, label, PSTR(label), ## __VA_ARGS__) + #define MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(type, label, ...) MENU_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## __VA_ARGS__) #endif //!ENCODER_RATE_MULTIPLIER /** Used variables to keep track of the menu */ @@ -354,10 +384,10 @@ uint8_t lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; // Set when the LCD needs to menuPosition screen_history[10]; uint8_t screen_history_depth = 0; + bool screen_changed; - bool ignore_click = false; - bool wait_for_unclick; - bool defer_return_to_status = false; + // LCD and menu clicks + bool lcd_clicked, wait_for_unclick, defer_return_to_status; // Variables used when editing values. const char* editLabel; @@ -366,29 +396,29 @@ uint8_t lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; // Set when the LCD needs to screenFunc_t callbackFunc; // call this after editing /** - * General function to go directly to a menu - * Remembers the previous position + * General function to go directly to a screen */ - static void lcd_goto_screen(screenFunc_t screen, const bool feedback = false, const uint32_t encoder = 0) { + void lcd_goto_screen(screenFunc_t screen, const uint32_t encoder = 0) { if (currentScreen != screen) { currentScreen = screen; - lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; encoderPosition = encoder; - if (feedback) lcd_quick_feedback(); if (screen == lcd_status_screen) { defer_return_to_status = false; screen_history_depth = 0; } + lcd_implementation_clear(); #if ENABLED(LCD_PROGRESS_BAR) // For LCD_PROGRESS_BAR re-initialize custom characters lcd_set_custom_characters(screen == lcd_status_screen); #endif + lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; + screen_changed = true; } } - static void lcd_return_to_status() { lcd_goto_screen(lcd_status_screen); } + void lcd_return_to_status() { lcd_goto_screen(lcd_status_screen); } - inline void lcd_save_previous_menu() { + void lcd_save_previous_screen() { if (screen_history_depth < COUNT(screen_history)) { screen_history[screen_history_depth].menu_function = currentScreen; screen_history[screen_history_depth].encoder_position = encoderPosition; @@ -396,12 +426,11 @@ uint8_t lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; // Set when the LCD needs to } } - static void lcd_goto_previous_menu(bool feedback=false) { + void lcd_goto_previous_menu() { if (screen_history_depth > 0) { --screen_history_depth; lcd_goto_screen( screen_history[screen_history_depth].menu_function, - feedback, screen_history[screen_history_depth].encoder_position ); } @@ -409,11 +438,6 @@ uint8_t lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; // Set when the LCD needs to lcd_return_to_status(); } - void lcd_ignore_click(bool b) { - ignore_click = b; - wait_for_unclick = false; - } - #endif // ULTIPANEL /** @@ -423,7 +447,7 @@ uint8_t lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; // Set when the LCD needs to * This is very display-dependent, so the lcd implementation draws this. */ -static void lcd_status_screen() { +void lcd_status_screen() { #if ENABLED(ULTIPANEL) ENCODER_DIRECTION_NORMAL(); @@ -467,32 +491,16 @@ static void lcd_status_screen() { #if ENABLED(ULTIPANEL) - bool current_click = LCD_CLICKED; - - if (ignore_click) { - if (wait_for_unclick) { - if (!current_click) - ignore_click = wait_for_unclick = false; - else - current_click = false; - } - else if (current_click) { - lcd_quick_feedback(); - wait_for_unclick = true; - current_click = false; - } - } - - if (current_click) { - lcd_goto_screen(lcd_main_menu, true); - lcd_implementation_init( // to maybe revive the LCD if static electricity killed it. - #if ENABLED(LCD_PROGRESS_BAR) && ENABLED(ULTIPANEL) - currentScreen == lcd_status_screen - #endif - ); + if (lcd_clicked) { #if ENABLED(FILAMENT_LCD_DISPLAY) previous_lcd_status_ms = millis(); // get status message to show up for a while #endif + lcd_implementation_init( // to maybe revive the LCD if static electricity killed it. + #if ENABLED(LCD_PROGRESS_BAR) + false + #endif + ); + lcd_goto_screen(lcd_main_menu); } #if ENABLED(ULTIPANEL_FEEDMULTIPLY) @@ -544,47 +552,73 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(ULTIPANEL) inline void line_to_current(AxisEnum axis) { - #if ENABLED(DELTA) - inverse_kinematics(current_position); - planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS], MMM_TO_MMS(manual_feedrate_mm_m[axis]), active_extruder); - #else // !DELTA - planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], MMM_TO_MMS(manual_feedrate_mm_m[axis]), active_extruder); - #endif // !DELTA + planner.buffer_line_kinematic(current_position, MMM_TO_MMS(manual_feedrate_mm_m[axis]), active_extruder); } #if ENABLED(SDSUPPORT) - static void lcd_sdcard_pause() { + void lcd_sdcard_pause() { card.pauseSDPrint(); print_job_timer.pause(); } - static void lcd_sdcard_resume() { + void lcd_sdcard_resume() { card.startFileprint(); print_job_timer.start(); } - static void lcd_sdcard_stop() { + void lcd_sdcard_stop() { card.stopSDPrint(); clear_command_queue(); quickstop_stepper(); print_job_timer.stop(); - thermalManager.autotempShutdown(); + #if ENABLED(AUTOTEMP) + thermalManager.autotempShutdown(); + #endif wait_for_heatup = false; lcd_setstatus(MSG_PRINT_ABORTED, true); } #endif //SDSUPPORT + #if ENABLED(MENU_ITEM_CASE_LIGHT) + + extern bool case_light_on; + extern void update_case_light(); + + void toggle_case_light() { + case_light_on = !case_light_on; + lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; + update_case_light(); + } + + #endif // MENU_ITEM_CASE_LIGHT + /** * * "Main" menu * */ - static void lcd_main_menu() { + void lcd_main_menu() { START_MENU(); - MENU_ITEM(back, MSG_WATCH); + MENU_BACK(MSG_WATCH); + + // + // Switch case light on/off + // + #if ENABLED(MENU_ITEM_CASE_LIGHT) + if (case_light_on) + MENU_ITEM(function, MSG_LIGHTS_OFF, toggle_case_light); + else + MENU_ITEM(function, MSG_LIGHTS_ON, toggle_case_light); + #endif + + #if ENABLED(BLTOUCH) + if (!endstops.z_probe_enabled && TEST_BLTOUCH()) + MENU_ITEM(gcode, MSG_BLTOUCH_RESET, PSTR("M280 P" STRINGIFY(Z_ENDSTOP_SERVO_NR) " S" STRINGIFY(BLTOUCH_RESET))); + #endif + if (planner.movesplanned() || IS_SD_PRINTING) { MENU_ITEM(submenu, MSG_TUNE, lcd_tune_menu); } @@ -646,11 +680,11 @@ void kill_screen(const char* lcd_msg) { long babysteps_done = 0; - static void _lcd_babystep(const AxisEnum axis, const char* msg) { - if (LCD_CLICKED) { lcd_goto_previous_menu(true); return; } + void _lcd_babystep(const AxisEnum axis, const char* msg) { + if (lcd_clicked) { defer_return_to_status = false; return lcd_goto_previous_menu(); } ENCODER_DIRECTION_NORMAL(); if (encoderPosition) { - int babystep_increment = (int32_t)encoderPosition * BABYSTEP_MULTIPLICATOR; + int babystep_increment = (int32_t)encoderPosition * (BABYSTEP_MULTIPLICATOR); encoderPosition = 0; lcdDrawUpdate = LCDVIEW_REDRAW_NOW; thermalManager.babystep_axis(axis, babystep_increment); @@ -663,13 +697,13 @@ void kill_screen(const char* lcd_msg) { } #if ENABLED(BABYSTEP_XY) - static void _lcd_babystep_x() { _lcd_babystep(X_AXIS, PSTR(MSG_BABYSTEPPING_X)); } - static void _lcd_babystep_y() { _lcd_babystep(Y_AXIS, PSTR(MSG_BABYSTEPPING_Y)); } - static void lcd_babystep_x() { babysteps_done = 0; lcd_goto_screen(_lcd_babystep_x); } - static void lcd_babystep_y() { babysteps_done = 0; lcd_goto_screen(_lcd_babystep_y); } + void _lcd_babystep_x() { _lcd_babystep(X_AXIS, PSTR(MSG_BABYSTEPPING_X)); } + void _lcd_babystep_y() { _lcd_babystep(Y_AXIS, PSTR(MSG_BABYSTEPPING_Y)); } + void lcd_babystep_x() { lcd_goto_screen(_lcd_babystep_x); babysteps_done = 0; defer_return_to_status = true; } + void lcd_babystep_y() { lcd_goto_screen(_lcd_babystep_y); babysteps_done = 0; defer_return_to_status = true; } #endif - static void _lcd_babystep_z() { _lcd_babystep(Z_AXIS, PSTR(MSG_BABYSTEPPING_Z)); } - static void lcd_babystep_z() { babysteps_done = 0; lcd_goto_screen(_lcd_babystep_z); } + void _lcd_babystep_z() { _lcd_babystep(Z_AXIS, PSTR(MSG_BABYSTEPPING_Z)); } + void lcd_babystep_z() { lcd_goto_screen(_lcd_babystep_z); babysteps_done = 0; defer_return_to_status = true; } #endif //BABYSTEPPING @@ -714,18 +748,25 @@ void kill_screen(const char* lcd_msg) { #endif #endif + #if ENABLED(FILAMENT_CHANGE_FEATURE) + void lcd_enqueue_filament_change() { + lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_INIT); + enqueue_and_echo_commands_P(PSTR("M600")); + } + #endif + /** * * "Tune" submenu * */ - static void lcd_tune_menu() { + void lcd_tune_menu() { START_MENU(); // // ^ Main // - MENU_ITEM(back, MSG_MAIN); + MENU_BACK(MSG_MAIN); // // Speed: @@ -799,15 +840,15 @@ void kill_screen(const char* lcd_msg) { // Flow 4: // #if EXTRUDERS == 1 - MENU_ITEM_EDIT(int3, MSG_FLOW, &extruder_multiplier[0], 10, 999); + MENU_ITEM_EDIT(int3, MSG_FLOW, &flow_percentage[0], 10, 999); #else // EXTRUDERS > 1 - MENU_ITEM_EDIT(int3, MSG_FLOW, &extruder_multiplier[active_extruder], 10, 999); - MENU_ITEM_EDIT(int3, MSG_FLOW MSG_N1, &extruder_multiplier[0], 10, 999); - MENU_ITEM_EDIT(int3, MSG_FLOW MSG_N2, &extruder_multiplier[1], 10, 999); + MENU_ITEM_EDIT(int3, MSG_FLOW, &flow_percentage[active_extruder], 10, 999); + MENU_ITEM_EDIT(int3, MSG_FLOW MSG_N1, &flow_percentage[0], 10, 999); + MENU_ITEM_EDIT(int3, MSG_FLOW MSG_N2, &flow_percentage[1], 10, 999); #if EXTRUDERS > 2 - MENU_ITEM_EDIT(int3, MSG_FLOW MSG_N3, &extruder_multiplier[2], 10, 999); + MENU_ITEM_EDIT(int3, MSG_FLOW MSG_N3, &flow_percentage[2], 10, 999); #if EXTRUDERS > 3 - MENU_ITEM_EDIT(int3, MSG_FLOW MSG_N4, &extruder_multiplier[3], 10, 999); + MENU_ITEM_EDIT(int3, MSG_FLOW MSG_N4, &flow_percentage[3], 10, 999); #endif //EXTRUDERS > 3 #endif //EXTRUDERS > 2 #endif //EXTRUDERS > 1 @@ -829,19 +870,46 @@ void kill_screen(const char* lcd_msg) { // Change filament // #if ENABLED(FILAMENT_CHANGE_FEATURE) - MENU_ITEM(gcode, MSG_FILAMENTCHANGE, PSTR("M600")); + MENU_ITEM(function, MSG_FILAMENTCHANGE, lcd_enqueue_filament_change); #endif END_MENU(); } + /** + * + * "Driver current control" submenu items + * + */ + #if ENABLED(DAC_STEPPER_CURRENT) + void dac_driver_getValues() { LOOP_XYZE(i) driverPercent[i] = dac_current_get_percent((AxisEnum)i); } + + void dac_driver_commit() { dac_current_set_percents(driverPercent); } + + void dac_driver_eeprom_write() { dac_commit_eeprom(); } + + void lcd_dac_menu() { + dac_driver_getValues(); + START_MENU(); + MENU_BACK(MSG_CONTROL); + MENU_ITEM_EDIT_CALLBACK(int3, MSG_X " " MSG_DAC_PERCENT, &driverPercent[X_AXIS], 0, 100, dac_driver_commit); + MENU_ITEM_EDIT_CALLBACK(int3, MSG_Y " " MSG_DAC_PERCENT, &driverPercent[Y_AXIS], 0, 100, dac_driver_commit); + MENU_ITEM_EDIT_CALLBACK(int3, MSG_Z " " MSG_DAC_PERCENT, &driverPercent[Z_AXIS], 0, 100, dac_driver_commit); + MENU_ITEM_EDIT_CALLBACK(int3, MSG_E " " MSG_DAC_PERCENT, &driverPercent[E_AXIS], 0, 100, dac_driver_commit); + MENU_ITEM(function, MSG_DAC_EEPROM_WRITE, dac_driver_eeprom_write); + END_MENU(); + } + #endif + + constexpr int heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP); + /** * * "Prepare" submenu items * */ void _lcd_preheat(int endnum, const float temph, const float tempb, const int fan) { - if (temph > 0) thermalManager.setTargetHotend(temph, endnum); + if (temph > 0) thermalManager.setTargetHotend(min(heater_maxtemp[endnum], temph), endnum); #if TEMP_SENSOR_BED != 0 thermalManager.setTargetBed(tempb); #else @@ -860,96 +928,96 @@ void kill_screen(const char* lcd_msg) { } #if TEMP_SENSOR_0 != 0 - void lcd_preheat_pla0() { _lcd_preheat(0, preheatHotendTemp1, preheatBedTemp1, preheatFanSpeed1); } - void lcd_preheat_abs0() { _lcd_preheat(0, preheatHotendTemp2, preheatBedTemp2, preheatFanSpeed2); } + void lcd_preheat_material1_hotend0() { _lcd_preheat(0, lcd_preheat_hotend_temp[0], lcd_preheat_bed_temp[0], lcd_preheat_fan_speed[0]); } + void lcd_preheat_material2_hotend0() { _lcd_preheat(0, lcd_preheat_hotend_temp[1], lcd_preheat_bed_temp[1], lcd_preheat_fan_speed[1]); } #endif #if HOTENDS > 1 - void lcd_preheat_pla1() { _lcd_preheat(1, preheatHotendTemp1, preheatBedTemp1, preheatFanSpeed1); } - void lcd_preheat_abs1() { _lcd_preheat(1, preheatHotendTemp2, preheatBedTemp2, preheatFanSpeed2); } + void lcd_preheat_material1_hotend1() { _lcd_preheat(1, lcd_preheat_hotend_temp[0], lcd_preheat_bed_temp[0], lcd_preheat_fan_speed[0]); } + void lcd_preheat_material2_hotend1() { _lcd_preheat(1, lcd_preheat_hotend_temp[1], lcd_preheat_bed_temp[1], lcd_preheat_fan_speed[1]); } #if HOTENDS > 2 - void lcd_preheat_pla2() { _lcd_preheat(2, preheatHotendTemp1, preheatBedTemp1, preheatFanSpeed1); } - void lcd_preheat_abs2() { _lcd_preheat(2, preheatHotendTemp2, preheatBedTemp2, preheatFanSpeed2); } + void lcd_preheat_material1_hotend2() { _lcd_preheat(2, lcd_preheat_hotend_temp[0], lcd_preheat_bed_temp[0], lcd_preheat_fan_speed[0]); } + void lcd_preheat_material2_hotend2() { _lcd_preheat(2, lcd_preheat_hotend_temp[1], lcd_preheat_bed_temp[1], lcd_preheat_fan_speed[1]); } #if HOTENDS > 3 - void lcd_preheat_pla3() { _lcd_preheat(3, preheatHotendTemp1, preheatBedTemp1, preheatFanSpeed1); } - void lcd_preheat_abs3() { _lcd_preheat(3, preheatHotendTemp2, preheatBedTemp2, preheatFanSpeed2); } + void lcd_preheat_material1_hotend3() { _lcd_preheat(3, lcd_preheat_hotend_temp[0], lcd_preheat_bed_temp[0], lcd_preheat_fan_speed[0]); } + void lcd_preheat_material2_hotend3() { _lcd_preheat(3, lcd_preheat_hotend_temp[1], lcd_preheat_bed_temp[1], lcd_preheat_fan_speed[1]); } #endif #endif - void lcd_preheat_pla0123() { + void lcd_preheat_material1_hotend0123() { #if HOTENDS > 1 - thermalManager.setTargetHotend(preheatHotendTemp1, 1); + thermalManager.setTargetHotend(lcd_preheat_hotend_temp[0], 1); #if HOTENDS > 2 - thermalManager.setTargetHotend(preheatHotendTemp1, 2); + thermalManager.setTargetHotend(lcd_preheat_hotend_temp[0], 2); #if HOTENDS > 3 - thermalManager.setTargetHotend(preheatHotendTemp1, 3); + thermalManager.setTargetHotend(lcd_preheat_hotend_temp[0], 3); #endif #endif #endif - lcd_preheat_pla0(); + lcd_preheat_material1_hotend0(); } - void lcd_preheat_abs0123() { + void lcd_preheat_material2_hotend0123() { #if HOTENDS > 1 - thermalManager.setTargetHotend(preheatHotendTemp2, 1); + thermalManager.setTargetHotend(lcd_preheat_hotend_temp[1], 1); #if HOTENDS > 2 - thermalManager.setTargetHotend(preheatHotendTemp2, 2); + thermalManager.setTargetHotend(lcd_preheat_hotend_temp[1], 2); #if HOTENDS > 3 - thermalManager.setTargetHotend(preheatHotendTemp2, 3); + thermalManager.setTargetHotend(lcd_preheat_hotend_temp[1], 3); #endif #endif #endif - lcd_preheat_abs0(); + lcd_preheat_material2_hotend0(); } #endif // HOTENDS > 1 #if TEMP_SENSOR_BED != 0 - void lcd_preheat_pla_bedonly() { _lcd_preheat(0, 0, preheatBedTemp1, preheatFanSpeed1); } - void lcd_preheat_abs_bedonly() { _lcd_preheat(0, 0, preheatBedTemp2, preheatFanSpeed2); } + void lcd_preheat_material1_bedonly() { _lcd_preheat(0, 0, lcd_preheat_bed_temp[0], lcd_preheat_fan_speed[0]); } + void lcd_preheat_material2_bedonly() { _lcd_preheat(0, 0, lcd_preheat_bed_temp[1], lcd_preheat_fan_speed[1]); } #endif #if TEMP_SENSOR_0 != 0 && (TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_BED != 0) - static void lcd_preheat_pla_menu() { + void lcd_preheat_material1_menu() { START_MENU(); - MENU_ITEM(back, MSG_PREPARE); + MENU_BACK(MSG_PREPARE); #if HOTENDS == 1 - MENU_ITEM(function, MSG_PREHEAT_1, lcd_preheat_pla0); + MENU_ITEM(function, MSG_PREHEAT_1, lcd_preheat_material1_hotend0); #else - MENU_ITEM(function, MSG_PREHEAT_1_N MSG_H1, lcd_preheat_pla0); - MENU_ITEM(function, MSG_PREHEAT_1_N MSG_H2, lcd_preheat_pla1); + MENU_ITEM(function, MSG_PREHEAT_1_N MSG_H1, lcd_preheat_material1_hotend0); + MENU_ITEM(function, MSG_PREHEAT_1_N MSG_H2, lcd_preheat_material1_hotend1); #if HOTENDS > 2 - MENU_ITEM(function, MSG_PREHEAT_1_N MSG_H3, lcd_preheat_pla2); + MENU_ITEM(function, MSG_PREHEAT_1_N MSG_H3, lcd_preheat_material1_hotend2); #if HOTENDS > 3 - MENU_ITEM(function, MSG_PREHEAT_1_N MSG_H4, lcd_preheat_pla3); + MENU_ITEM(function, MSG_PREHEAT_1_N MSG_H4, lcd_preheat_material1_hotend3); #endif #endif - MENU_ITEM(function, MSG_PREHEAT_1_ALL, lcd_preheat_pla0123); + MENU_ITEM(function, MSG_PREHEAT_1_ALL, lcd_preheat_material1_hotend0123); #endif #if TEMP_SENSOR_BED != 0 - MENU_ITEM(function, MSG_PREHEAT_1_BEDONLY, lcd_preheat_pla_bedonly); + MENU_ITEM(function, MSG_PREHEAT_1_BEDONLY, lcd_preheat_material1_bedonly); #endif END_MENU(); } - static void lcd_preheat_abs_menu() { + void lcd_preheat_material2_menu() { START_MENU(); - MENU_ITEM(back, MSG_PREPARE); + MENU_BACK(MSG_PREPARE); #if HOTENDS == 1 - MENU_ITEM(function, MSG_PREHEAT_2, lcd_preheat_abs0); + MENU_ITEM(function, MSG_PREHEAT_2, lcd_preheat_material2_hotend0); #else - MENU_ITEM(function, MSG_PREHEAT_2_N MSG_H1, lcd_preheat_abs0); - MENU_ITEM(function, MSG_PREHEAT_2_N MSG_H2, lcd_preheat_abs1); + MENU_ITEM(function, MSG_PREHEAT_2_N MSG_H1, lcd_preheat_material2_hotend0); + MENU_ITEM(function, MSG_PREHEAT_2_N MSG_H2, lcd_preheat_material2_hotend1); #if HOTENDS > 2 - MENU_ITEM(function, MSG_PREHEAT_2_N MSG_H3, lcd_preheat_abs2); + MENU_ITEM(function, MSG_PREHEAT_2_N MSG_H3, lcd_preheat_material2_hotend2); #if HOTENDS > 3 - MENU_ITEM(function, MSG_PREHEAT_2_N MSG_H4, lcd_preheat_abs3); + MENU_ITEM(function, MSG_PREHEAT_2_N MSG_H4, lcd_preheat_material2_hotend3); #endif #endif - MENU_ITEM(function, MSG_PREHEAT_2_ALL, lcd_preheat_abs0123); + MENU_ITEM(function, MSG_PREHEAT_2_ALL, lcd_preheat_material2_hotend0123); #endif #if TEMP_SENSOR_BED != 0 - MENU_ITEM(function, MSG_PREHEAT_2_BEDONLY, lcd_preheat_abs_bedonly); + MENU_ITEM(function, MSG_PREHEAT_2_BEDONLY, lcd_preheat_material2_bedonly); #endif END_MENU(); } @@ -966,7 +1034,7 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(SDSUPPORT) && ENABLED(MENU_ADDAUTOSTART) - static void lcd_autostart_sd() { + void lcd_autostart_sd() { card.autostart_index = 0; card.setroot(); card.checkautostart(true); @@ -989,21 +1057,21 @@ void kill_screen(const char* lcd_msg) { // Note: During Manual Bed Leveling the homed Z position is MESH_HOME_SEARCH_Z // Z position will be restored with the final action, a G28 inline void _mbl_goto_xy(float x, float y) { - current_position[Z_AXIS] = MESH_HOME_SEARCH_Z + Z_HOMING_HEIGHT; + current_position[Z_AXIS] = LOGICAL_Z_POSITION(MESH_HOME_SEARCH_Z + Z_HOMING_HEIGHT); line_to_current(Z_AXIS); - current_position[X_AXIS] = x + home_offset[X_AXIS]; - current_position[Y_AXIS] = y + home_offset[Y_AXIS]; - line_to_current(manual_feedrate_mm_m[X_AXIS] <= manual_feedrate_mm_m[Y_AXIS] ? X_AXIS : Y_AXIS); + current_position[X_AXIS] = LOGICAL_X_POSITION(x); + current_position[Y_AXIS] = LOGICAL_Y_POSITION(y); + planner.buffer_line_kinematic(current_position, MMM_TO_MMS(XY_PROBE_SPEED), active_extruder); #if Z_HOMING_HEIGHT > 0 - current_position[Z_AXIS] = MESH_HOME_SEARCH_Z; // How do condition and action match? + current_position[Z_AXIS] = LOGICAL_Z_POSITION(MESH_HOME_SEARCH_Z); line_to_current(Z_AXIS); #endif stepper.synchronize(); } - static void _lcd_level_goto_next_point(); + void _lcd_level_goto_next_point(); - static void _lcd_level_bed_done() { + void _lcd_level_bed_done() { if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR(MSG_LEVEL_BED_DONE)); lcdDrawUpdate = #if ENABLED(DOGLCD) @@ -1017,7 +1085,7 @@ void kill_screen(const char* lcd_msg) { /** * Step 7: Get the Z coordinate, then goto next point or exit */ - static void _lcd_level_bed_get_z() { + void _lcd_level_bed_get_z() { ENCODER_DIRECTION_NORMAL(); // Encoder wheel adjusts the Z position @@ -1038,12 +1106,12 @@ void kill_screen(const char* lcd_msg) { } static bool debounce_click = false; - if (LCD_CLICKED) { + if (lcd_clicked) { if (!debounce_click) { debounce_click = true; // ignore multiple "clicks" in a row mbl.set_zigzag_z(_lcd_level_bed_position++, current_position[Z_AXIS]); if (_lcd_level_bed_position == (MESH_NUM_X_POINTS) * (MESH_NUM_Y_POINTS)) { - lcd_goto_screen(_lcd_level_bed_done, true); + lcd_goto_screen(_lcd_level_bed_done); current_position[Z_AXIS] = MESH_HOME_SEARCH_Z + Z_HOMING_HEIGHT; line_to_current(Z_AXIS); @@ -1059,7 +1127,7 @@ void kill_screen(const char* lcd_msg) { #endif } else { - lcd_goto_screen(_lcd_level_goto_next_point, true); + lcd_goto_screen(_lcd_level_goto_next_point); } } } @@ -1079,7 +1147,7 @@ void kill_screen(const char* lcd_msg) { /** * Step 6: Display "Next point: 1 / 9" while waiting for move to finish */ - static void _lcd_level_bed_moving() { + void _lcd_level_bed_moving() { if (lcdDrawUpdate) { char msg[10]; sprintf_P(msg, PSTR("%i / %u"), (int)(_lcd_level_bed_position + 1), (MESH_NUM_X_POINTS) * (MESH_NUM_Y_POINTS)); @@ -1098,7 +1166,7 @@ void kill_screen(const char* lcd_msg) { /** * Step 5: Initiate a move to the next point */ - static void _lcd_level_goto_next_point() { + void _lcd_level_goto_next_point() { // Set the menu to display ahead of blocking call lcd_goto_screen(_lcd_level_bed_moving); @@ -1115,9 +1183,9 @@ void kill_screen(const char* lcd_msg) { * Step 4: Display "Click to Begin", wait for click * Move to the first probe position */ - static void _lcd_level_bed_homing_done() { + void _lcd_level_bed_homing_done() { if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR(MSG_LEVEL_BED_WAITING)); - if (LCD_CLICKED) { + if (lcd_clicked) { _lcd_level_bed_position = 0; current_position[Z_AXIS] = MESH_HOME_SEARCH_Z #if Z_HOME_DIR > 0 @@ -1125,14 +1193,14 @@ void kill_screen(const char* lcd_msg) { #endif ; planner.set_position_mm(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); - lcd_goto_screen(_lcd_level_goto_next_point, true); + lcd_goto_screen(_lcd_level_goto_next_point); } } /** * Step 3: Display "Homing XYZ" - Wait for homing to finish */ - static void _lcd_level_bed_homing() { + void _lcd_level_bed_homing() { if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR(MSG_LEVEL_BED_HOMING), NULL); lcdDrawUpdate = #if ENABLED(DOGLCD) @@ -1148,7 +1216,7 @@ void kill_screen(const char* lcd_msg) { /** * Step 2: Continue Bed Leveling... */ - static void _lcd_level_bed_continue() { + void _lcd_level_bed_continue() { defer_return_to_status = true; axis_homed[X_AXIS] = axis_homed[Y_AXIS] = axis_homed[Z_AXIS] = false; mbl.reset(); @@ -1159,9 +1227,9 @@ void kill_screen(const char* lcd_msg) { /** * Step 1: MBL entry-point: "Cancel" or "Level Bed" */ - static void lcd_level_bed() { + void lcd_level_bed() { START_MENU(); - MENU_ITEM(back, MSG_LEVEL_BED_CANCEL); + MENU_BACK(MSG_LEVEL_BED_CANCEL); MENU_ITEM(submenu, MSG_LEVEL_BED, _lcd_level_bed_continue); END_MENU(); } @@ -1174,13 +1242,13 @@ void kill_screen(const char* lcd_msg) { * */ - static void lcd_prepare_menu() { + void lcd_prepare_menu() { START_MENU(); // // ^ Main // - MENU_ITEM(back, MSG_MAIN); + MENU_BACK(MSG_MAIN); // // Auto Home @@ -1201,7 +1269,7 @@ void kill_screen(const char* lcd_msg) { // // Level Bed // - #if ENABLED(AUTO_BED_LEVELING_FEATURE) + #if HAS_ABL MENU_ITEM(gcode, MSG_LEVEL_BED, axis_homed[X_AXIS] && axis_homed[Y_AXIS] ? PSTR("G29") : PSTR("G28\nG29") ); @@ -1225,11 +1293,11 @@ void kill_screen(const char* lcd_msg) { // #if TEMP_SENSOR_0 != 0 #if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_BED != 0 - MENU_ITEM(submenu, MSG_PREHEAT_1, lcd_preheat_pla_menu); - MENU_ITEM(submenu, MSG_PREHEAT_2, lcd_preheat_abs_menu); + MENU_ITEM(submenu, MSG_PREHEAT_1, lcd_preheat_material1_menu); + MENU_ITEM(submenu, MSG_PREHEAT_2, lcd_preheat_material2_menu); #else - MENU_ITEM(function, MSG_PREHEAT_1, lcd_preheat_pla0); - MENU_ITEM(function, MSG_PREHEAT_2, lcd_preheat_abs0); + MENU_ITEM(function, MSG_PREHEAT_1, lcd_preheat_material1_hotend0); + MENU_ITEM(function, MSG_PREHEAT_2, lcd_preheat_material2_hotend0); #endif #endif @@ -1238,6 +1306,15 @@ void kill_screen(const char* lcd_msg) { // MENU_ITEM(function, MSG_COOLDOWN, lcd_cooldown); + // + // BLTouch Self-Test and Reset + // + #if ENABLED(BLTOUCH) + MENU_ITEM(gcode, MSG_BLTOUCH_SELFTEST, PSTR("M280 P" STRINGIFY(Z_ENDSTOP_SERVO_NR) " S" STRINGIFY(BLTOUCH_SELFTEST))); + if (!endstops.z_probe_enabled && TEST_BLTOUCH()) + MENU_ITEM(gcode, MSG_BLTOUCH_RESET, PSTR("M280 P" STRINGIFY(Z_ENDSTOP_SERVO_NR) " S" STRINGIFY(BLTOUCH_RESET))); + #endif + // // Switch power on/off // @@ -1260,14 +1337,27 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(DELTA_CALIBRATION_MENU) - static void lcd_delta_calibrate_menu() { + void _goto_tower_pos(const float &a) { + do_blocking_move_to( + a < 0 ? X_HOME_POS : sin(a) * -(DELTA_PRINTABLE_RADIUS), + a < 0 ? Y_HOME_POS : cos(a) * (DELTA_PRINTABLE_RADIUS), + 4 + ); + } + + void _goto_tower_x() { _goto_tower_pos(RADIANS(120)); } + void _goto_tower_y() { _goto_tower_pos(RADIANS(240)); } + void _goto_tower_z() { _goto_tower_pos(0); } + void _goto_center() { _goto_tower_pos(-1); } + + void lcd_delta_calibrate_menu() { START_MENU(); - MENU_ITEM(back, MSG_MAIN); + MENU_BACK(MSG_MAIN); MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28")); - MENU_ITEM(gcode, MSG_DELTA_CALIBRATE_X, PSTR("G0 F8000 X-77.94 Y-45 Z0")); - MENU_ITEM(gcode, MSG_DELTA_CALIBRATE_Y, PSTR("G0 F8000 X77.94 Y-45 Z0")); - MENU_ITEM(gcode, MSG_DELTA_CALIBRATE_Z, PSTR("G0 F8000 X0 Y90 Z0")); - MENU_ITEM(gcode, MSG_DELTA_CALIBRATE_CENTER, PSTR("G0 F8000 X0 Y0 Z0")); + MENU_ITEM(function, MSG_DELTA_CALIBRATE_X, _goto_tower_x); + MENU_ITEM(function, MSG_DELTA_CALIBRATE_Y, _goto_tower_y); + MENU_ITEM(function, MSG_DELTA_CALIBRATE_Z, _goto_tower_z); + MENU_ITEM(function, MSG_DELTA_CALIBRATE_CENTER, _goto_center); END_MENU(); } @@ -1281,12 +1371,7 @@ void kill_screen(const char* lcd_msg) { */ inline void manage_manual_move() { if (manual_move_axis != (int8_t)NO_AXIS && ELAPSED(millis(), manual_move_start_time) && !planner.is_full()) { - #if ENABLED(DELTA) - inverse_kinematics(current_position); - planner.buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS], MMM_TO_MMS(manual_feedrate_mm_m[manual_move_axis]), manual_move_e_index); - #else - planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], MMM_TO_MMS(manual_feedrate_mm_m[manual_move_axis]), manual_move_e_index); - #endif + planner.buffer_line_kinematic(current_position, MMM_TO_MMS(manual_feedrate_mm_m[manual_move_axis]), manual_move_e_index); manual_move_axis = (int8_t)NO_AXIS; } } @@ -1313,36 +1398,48 @@ void kill_screen(const char* lcd_msg) { * */ - static void _lcd_move_xyz(const char* name, AxisEnum axis, float min, float max) { - if (LCD_CLICKED) { lcd_goto_previous_menu(true); return; } + void _lcd_move_xyz(const char* name, AxisEnum axis) { + if (lcd_clicked) { return lcd_goto_previous_menu(); } ENCODER_DIRECTION_NORMAL(); if (encoderPosition) { refresh_cmd_timeout(); + + // Limit to software endstops, if enabled + float min = (soft_endstops_enabled && min_software_endstops) ? soft_endstop_min[axis] : current_position[axis] - 1000, + max = (soft_endstops_enabled && max_software_endstops) ? soft_endstop_max[axis] : current_position[axis] + 1000; + + // Get the new position current_position[axis] += float((int32_t)encoderPosition) * move_menu_scale; - if (min_software_endstops) NOLESS(current_position[axis], min); - if (max_software_endstops) NOMORE(current_position[axis], max); - encoderPosition = 0; + + // Delta limits XY based on the current offset from center + // This assumes the center is 0,0 + #if ENABLED(DELTA) + if (axis != Z_AXIS) { + max = sqrt(sq(DELTA_PRINTABLE_RADIUS) - sq(current_position[Y_AXIS - axis])); + min = -max; + } + #endif + + // Limit only when trying to move towards the limit + if ((int32_t)encoderPosition < 0) NOLESS(current_position[axis], min); + if ((int32_t)encoderPosition > 0) NOMORE(current_position[axis], max); + manual_move_to_current(axis); + + encoderPosition = 0; lcdDrawUpdate = LCDVIEW_REDRAW_NOW; } if (lcdDrawUpdate) lcd_implementation_drawedit(name, ftostr41sign(current_position[axis])); } - #if ENABLED(DELTA) - static float delta_clip_radius_2 = (DELTA_PRINTABLE_RADIUS) * (DELTA_PRINTABLE_RADIUS); - static int delta_clip( float a ) { return sqrt(delta_clip_radius_2 - sq(a)); } - static void lcd_move_x() { int clip = delta_clip(current_position[Y_AXIS]); _lcd_move_xyz(PSTR(MSG_MOVE_X), X_AXIS, max(sw_endstop_min[X_AXIS], -clip), min(sw_endstop_max[X_AXIS], clip)); } - static void lcd_move_y() { int clip = delta_clip(current_position[X_AXIS]); _lcd_move_xyz(PSTR(MSG_MOVE_Y), Y_AXIS, max(sw_endstop_min[Y_AXIS], -clip), min(sw_endstop_max[Y_AXIS], clip)); } - #else - static void lcd_move_x() { _lcd_move_xyz(PSTR(MSG_MOVE_X), X_AXIS, sw_endstop_min[X_AXIS], sw_endstop_max[X_AXIS]); } - static void lcd_move_y() { _lcd_move_xyz(PSTR(MSG_MOVE_Y), Y_AXIS, sw_endstop_min[Y_AXIS], sw_endstop_max[Y_AXIS]); } - #endif - static void lcd_move_z() { _lcd_move_xyz(PSTR(MSG_MOVE_Z), Z_AXIS, sw_endstop_min[Z_AXIS], sw_endstop_max[Z_AXIS]); } - static void _lcd_move_e( + void lcd_move_x() { _lcd_move_xyz(PSTR(MSG_MOVE_X), X_AXIS); } + void lcd_move_y() { _lcd_move_xyz(PSTR(MSG_MOVE_Y), Y_AXIS); } + void lcd_move_z() { _lcd_move_xyz(PSTR(MSG_MOVE_Z), Z_AXIS); } + void _lcd_move_e( #if E_MANUAL > 1 int8_t eindex=-1 #endif ) { - if (LCD_CLICKED) { lcd_goto_previous_menu(true); return; } + if (lcd_clicked) { return lcd_goto_previous_menu(); } ENCODER_DIRECTION_NORMAL(); if (encoderPosition) { current_position[E_AXIS] += float((int32_t)encoderPosition) * move_menu_scale; @@ -1374,14 +1471,14 @@ void kill_screen(const char* lcd_msg) { } } - static void lcd_move_e() { _lcd_move_e(); } + void lcd_move_e() { _lcd_move_e(); } #if E_MANUAL > 1 - static void lcd_move_e0() { _lcd_move_e(0); } - static void lcd_move_e1() { _lcd_move_e(1); } + void lcd_move_e0() { _lcd_move_e(0); } + void lcd_move_e1() { _lcd_move_e(1); } #if E_MANUAL > 2 - static void lcd_move_e2() { _lcd_move_e(2); } + void lcd_move_e2() { _lcd_move_e(2); } #if E_MANUAL > 3 - static void lcd_move_e3() { _lcd_move_e(3); } + void lcd_move_e3() { _lcd_move_e(3); } #endif #endif #endif @@ -1392,15 +1489,15 @@ void kill_screen(const char* lcd_msg) { * */ - #if ENABLED(DELTA) || ENABLED(SCARA) + #if IS_KINEMATIC #define _MOVE_XYZ_ALLOWED (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) #else #define _MOVE_XYZ_ALLOWED true #endif - static void _lcd_move_menu_axis() { + void _lcd_move_menu_axis() { START_MENU(); - MENU_ITEM(back, MSG_MOVE_AXIS); + MENU_BACK(MSG_MOVE_AXIS); if (_MOVE_XYZ_ALLOWED) { MENU_ITEM(submenu, MSG_MOVE_X, lcd_move_x); @@ -1432,15 +1529,15 @@ void kill_screen(const char* lcd_msg) { END_MENU(); } - static void lcd_move_menu_10mm() { + void lcd_move_menu_10mm() { move_menu_scale = 10.0; _lcd_move_menu_axis(); } - static void lcd_move_menu_1mm() { + void lcd_move_menu_1mm() { move_menu_scale = 1.0; _lcd_move_menu_axis(); } - static void lcd_move_menu_01mm() { + void lcd_move_menu_01mm() { move_menu_scale = 0.1; _lcd_move_menu_axis(); } @@ -1451,9 +1548,9 @@ void kill_screen(const char* lcd_msg) { * */ - static void lcd_move_menu() { + void lcd_move_menu() { START_MENU(); - MENU_ITEM(back, MSG_PREPARE); + MENU_BACK(MSG_PREPARE); if (_MOVE_XYZ_ALLOWED) MENU_ITEM(submenu, MSG_MOVE_10MM, lcd_move_menu_10mm); @@ -1470,9 +1567,9 @@ void kill_screen(const char* lcd_msg) { * */ - static void lcd_control_menu() { + void lcd_control_menu() { START_MENU(); - MENU_ITEM(back, MSG_MAIN); + MENU_BACK(MSG_MAIN); MENU_ITEM(submenu, MSG_TEMPERATURE, lcd_control_temperature_menu); MENU_ITEM(submenu, MSG_MOTION, lcd_control_motion_menu); MENU_ITEM(submenu, MSG_VOLUMETRIC, lcd_control_volumetric_menu); @@ -1484,6 +1581,10 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(FWRETRACT) MENU_ITEM(submenu, MSG_RETRACT, lcd_control_retract_menu); #endif + #if ENABLED(DAC_STEPPER_CURRENT) + MENU_ITEM(submenu, MSG_DRIVE_STRENGTH, lcd_dac_menu); + #endif + #if ENABLED(EEPROM_SETTINGS) MENU_ITEM(function, MSG_STORE_EPROM, Config_StoreSettings); MENU_ITEM(function, MSG_LOAD_EPROM, Config_RetrieveSettings); @@ -1502,14 +1603,13 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(PIDTEMP) int autotune_temp[HOTENDS] = ARRAY_BY_HOTENDS1(150); - const int heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP); #endif #if ENABLED(PIDTEMPBED) int autotune_temp_bed = 70; #endif - static void _lcd_autotune(int e) { + void _lcd_autotune(int e) { char cmd[30]; sprintf_P(cmd, PSTR("M303 U1 E%i S%i"), e, #if HAS_PID_FOR_BOTH @@ -1555,14 +1655,14 @@ void kill_screen(const char* lcd_msg) { #define _PIDTEMP_FUNCTIONS(eindex) _PIDTEMP_BASE_FUNCTIONS(eindex) #endif - _PIDTEMP_FUNCTIONS(0); + _PIDTEMP_FUNCTIONS(0) #if ENABLED(PID_PARAMS_PER_HOTEND) #if HOTENDS > 1 - _PIDTEMP_FUNCTIONS(1); + _PIDTEMP_FUNCTIONS(1) #if HOTENDS > 2 - _PIDTEMP_FUNCTIONS(2); + _PIDTEMP_FUNCTIONS(2) #if HOTENDS > 3 - _PIDTEMP_FUNCTIONS(3); + _PIDTEMP_FUNCTIONS(3) #endif //HOTENDS > 3 #endif //HOTENDS > 2 #endif //HOTENDS > 1 @@ -1575,13 +1675,13 @@ void kill_screen(const char* lcd_msg) { * "Control" > "Temperature" submenu * */ - static void lcd_control_temperature_menu() { + void lcd_control_temperature_menu() { START_MENU(); // // ^ Control // - MENU_ITEM(back, MSG_CONTROL); + MENU_BACK(MSG_CONTROL); // // Nozzle: @@ -1614,7 +1714,7 @@ void kill_screen(const char* lcd_msg) { // Bed: // #if TEMP_SENSOR_BED != 0 - MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_BED, &thermalManager.target_temperature_bed, 0, BED_MAXTEMP - 15); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(int3, MSG_BED, &thermalManager.target_temperature_bed, 0, BED_MAXTEMP - 15, watch_temp_callback_bed); #endif // @@ -1695,31 +1795,39 @@ void kill_screen(const char* lcd_msg) { #endif //PIDTEMP // - // Preheat PLA conf + // Preheat Material 1 conf // - MENU_ITEM(submenu, MSG_PREHEAT_1_SETTINGS, lcd_control_temperature_preheat_pla_settings_menu); + MENU_ITEM(submenu, MSG_PREHEAT_1_SETTINGS, lcd_control_temperature_preheat_material1_settings_menu); // - // Preheat ABS conf + // Preheat Material 2 conf // - MENU_ITEM(submenu, MSG_PREHEAT_2_SETTINGS, lcd_control_temperature_preheat_abs_settings_menu); + MENU_ITEM(submenu, MSG_PREHEAT_2_SETTINGS, lcd_control_temperature_preheat_material2_settings_menu); END_MENU(); } - /** - * - * "Temperature" > "Preheat PLA conf" submenu - * - */ - static void lcd_control_temperature_preheat_pla_settings_menu() { + void _lcd_control_temperature_preheat_settings_menu(uint8_t material) { + #if HOTENDS > 3 + #define MINTEMP_ALL MIN4(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP, HEATER_3_MINTEMP) + #define MAXTEMP_ALL MAX4(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP) + #elif HOTENDS > 2 + #define MINTEMP_ALL MIN3(HEATER_0_MINTEMP, HEATER_1_MINTEMP, HEATER_2_MINTEMP) + #define MAXTEMP_ALL MAX3(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP) + #elif HOTENDS > 1 + #define MINTEMP_ALL min(HEATER_0_MINTEMP, HEATER_1_MINTEMP) + #define MAXTEMP_ALL max(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP) + #else + #define MINTEMP_ALL HEATER_0_MINTEMP + #define MAXTEMP_ALL HEATER_0_MAXTEMP + #endif START_MENU(); - MENU_ITEM(back, MSG_TEMPERATURE); - MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &preheatFanSpeed1, 0, 255); + MENU_BACK(MSG_TEMPERATURE); + MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &lcd_preheat_fan_speed[material], 0, 255); #if TEMP_SENSOR_0 != 0 - MENU_ITEM_EDIT(int3, MSG_NOZZLE, &preheatHotendTemp1, HEATER_0_MINTEMP, HEATER_0_MAXTEMP - 15); + MENU_ITEM_EDIT(int3, MSG_NOZZLE, &lcd_preheat_hotend_temp[material], MINTEMP_ALL, MAXTEMP_ALL - 15); #endif #if TEMP_SENSOR_BED != 0 - MENU_ITEM_EDIT(int3, MSG_BED, &preheatBedTemp1, BED_MINTEMP, BED_MAXTEMP - 15); + MENU_ITEM_EDIT(int3, MSG_BED, &lcd_preheat_bed_temp[material], BED_MINTEMP, BED_MAXTEMP - 15); #endif #if ENABLED(EEPROM_SETTINGS) MENU_ITEM(function, MSG_STORE_EPROM, Config_StoreSettings); @@ -1729,36 +1837,57 @@ void kill_screen(const char* lcd_msg) { /** * - * "Temperature" > "Preheat ABS conf" submenu + * "Temperature" > "Preheat Material 1 conf" submenu * */ - static void lcd_control_temperature_preheat_abs_settings_menu() { - START_MENU(); - MENU_ITEM(back, MSG_TEMPERATURE); - MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &preheatFanSpeed2, 0, 255); - #if TEMP_SENSOR_0 != 0 - MENU_ITEM_EDIT(int3, MSG_NOZZLE, &preheatHotendTemp2, HEATER_0_MINTEMP, HEATER_0_MAXTEMP - 15); - #endif - #if TEMP_SENSOR_BED != 0 - MENU_ITEM_EDIT(int3, MSG_BED, &preheatBedTemp2, BED_MINTEMP, BED_MAXTEMP - 15); - #endif - #if ENABLED(EEPROM_SETTINGS) - MENU_ITEM(function, MSG_STORE_EPROM, Config_StoreSettings); - #endif - END_MENU(); - } + void lcd_control_temperature_preheat_material1_settings_menu() { _lcd_control_temperature_preheat_settings_menu(0); } - static void _reset_acceleration_rates() { planner.reset_acceleration_rates(); } - static void _planner_refresh_positioning() { planner.refresh_positioning(); } + /** + * + * "Temperature" > "Preheat Material 2 conf" submenu + * + */ + void lcd_control_temperature_preheat_material2_settings_menu() { _lcd_control_temperature_preheat_settings_menu(1); } + + void _reset_acceleration_rates() { planner.reset_acceleration_rates(); } + #if ENABLED(DISTINCT_E_FACTORS) + void _reset_e_acceleration_rate(const uint8_t e) { if (e == active_extruder) _reset_acceleration_rates(); } + void _reset_e0_acceleration_rate() { _reset_e_acceleration_rate(0); } + void _reset_e1_acceleration_rate() { _reset_e_acceleration_rate(1); } + #if E_STEPPERS > 2 + void _reset_e2_acceleration_rate() { _reset_e_acceleration_rate(2); } + #if E_STEPPERS > 3 + void _reset_e3_acceleration_rate() { _reset_e_acceleration_rate(3); } + #endif + #endif + #endif + + void _planner_refresh_positioning() { planner.refresh_positioning(); } + #if ENABLED(DISTINCT_E_FACTORS) + void _planner_refresh_e_positioning(const uint8_t e) { + if (e == active_extruder) + _planner_refresh_positioning(); + else + planner.steps_to_mm[i] = 1.0 / planner.axis_steps_per_mm[i]; + } + void _planner_refresh_e0_positioning() { _reset_e_acceleration_rate(0); } + void _planner_refresh_e1_positioning() { _reset_e_acceleration_rate(1); } + #if E_STEPPERS > 2 + void _planner_refresh_e2_positioning() { _reset_e_acceleration_rate(2); } + #if E_STEPPERS > 3 + void _planner_refresh_e3_positioning() { _reset_e_acceleration_rate(3); } + #endif + #endif + #endif /** * * "Control" > "Motion" submenu * */ - static void lcd_control_motion_menu() { + void lcd_control_motion_menu() { START_MENU(); - MENU_ITEM(back, MSG_CONTROL); + MENU_BACK(MSG_CONTROL); #if HAS_BED_PROBE MENU_ITEM_EDIT(float32, MSG_ZPROBE_ZOFFSET, &zprobe_zoffset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX); #endif @@ -1767,40 +1896,87 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM_EDIT(float43, MSG_BED_Z, &mbl.z_offset, -1, 1); #endif MENU_ITEM_EDIT(float5, MSG_ACC, &planner.acceleration, 10, 99000); - MENU_ITEM_EDIT(float3, MSG_VXY_JERK, &planner.max_xy_jerk, 1, 990); + MENU_ITEM_EDIT(float3, MSG_VX_JERK, &planner.max_jerk[X_AXIS], 1, 990); + MENU_ITEM_EDIT(float3, MSG_VY_JERK, &planner.max_jerk[Y_AXIS], 1, 990); #if ENABLED(DELTA) - MENU_ITEM_EDIT(float3, MSG_VZ_JERK, &planner.max_z_jerk, 1, 990); + MENU_ITEM_EDIT(float3, MSG_VZ_JERK, &planner.max_jerk[Z_AXIS], 1, 990); #else - MENU_ITEM_EDIT(float52, MSG_VZ_JERK, &planner.max_z_jerk, 0.1, 990); + MENU_ITEM_EDIT(float52, MSG_VZ_JERK, &planner.max_jerk[Z_AXIS], 0.1, 990); #endif - MENU_ITEM_EDIT(float3, MSG_VE_JERK, &planner.max_e_jerk, 1, 990); + MENU_ITEM_EDIT(float3, MSG_VE_JERK, &planner.max_jerk[E_AXIS], 1, 990); + + // + // M203 Settings + // MENU_ITEM_EDIT(float3, MSG_VMAX MSG_X, &planner.max_feedrate_mm_s[X_AXIS], 1, 999); MENU_ITEM_EDIT(float3, MSG_VMAX MSG_Y, &planner.max_feedrate_mm_s[Y_AXIS], 1, 999); MENU_ITEM_EDIT(float3, MSG_VMAX MSG_Z, &planner.max_feedrate_mm_s[Z_AXIS], 1, 999); - MENU_ITEM_EDIT(float3, MSG_VMAX MSG_E, &planner.max_feedrate_mm_s[E_AXIS], 1, 999); + + #if ENABLED(DISTINCT_E_FACTORS) + MENU_ITEM_EDIT(float3, MSG_VMAX MSG_E, &planner.max_feedrate_mm_s[E_AXIS + active_extruder], 1, 999); + MENU_ITEM_EDIT(float3, MSG_VMAX MSG_E1, &planner.max_feedrate_mm_s[E_AXIS], 1, 999); + MENU_ITEM_EDIT(float3, MSG_VMAX MSG_E2, &planner.max_feedrate_mm_s[E_AXIS + 1], 1, 999); + #if E_STEPPERS > 2 + MENU_ITEM_EDIT(float3, MSG_VMAX MSG_E3, &planner.max_feedrate_mm_s[E_AXIS + 2], 1, 999); + #if E_STEPPERS > 3 + MENU_ITEM_EDIT(float3, MSG_VMAX MSG_E3, &planner.max_feedrate_mm_s[E_AXIS + 3], 1, 999); + #endif + #endif + #else + MENU_ITEM_EDIT(float3, MSG_VMAX MSG_E, &planner.max_feedrate_mm_s[E_AXIS], 1, 999); + #endif + MENU_ITEM_EDIT(float3, MSG_VMIN, &planner.min_feedrate_mm_s, 0, 999); MENU_ITEM_EDIT(float3, MSG_VTRAV_MIN, &planner.min_travel_feedrate_mm_s, 0, 999); + + // + // M201 Settings + // MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_X, &planner.max_acceleration_mm_per_s2[X_AXIS], 100, 99000, _reset_acceleration_rates); MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_Y, &planner.max_acceleration_mm_per_s2[Y_AXIS], 100, 99000, _reset_acceleration_rates); MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_Z, &planner.max_acceleration_mm_per_s2[Z_AXIS], 10, 99000, _reset_acceleration_rates); - MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_E, &planner.max_acceleration_mm_per_s2[E_AXIS], 100, 99000, _reset_acceleration_rates); + + #if ENABLED(DISTINCT_E_FACTORS) + MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_E, &planner.max_acceleration_mm_per_s2[E_AXIS + active_extruder], 100, 99000, _reset_acceleration_rates); + MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_E1, &planner.max_acceleration_mm_per_s2[E_AXIS], 100, 99000, _reset_e0_acceleration_rate); + MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_E2, &planner.max_acceleration_mm_per_s2[E_AXIS + 1], 100, 99000, _reset_e1_acceleration_rate); + #if E_STEPPERS > 2 + MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_E3, &planner.max_acceleration_mm_per_s2[E_AXIS + 2], 100, 99000, _reset_e2_acceleration_rate); + #if E_STEPPERS > 3 + MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_E4, &planner.max_acceleration_mm_per_s2[E_AXIS + 3], 100, 99000, _reset_e3_acceleration_rate); + #endif + #endif + #else + MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_E, &planner.max_acceleration_mm_per_s2[E_AXIS], 100, 99000, _reset_acceleration_rates); + #endif + MENU_ITEM_EDIT(float5, MSG_A_RETRACT, &planner.retract_acceleration, 100, 99000); MENU_ITEM_EDIT(float5, MSG_A_TRAVEL, &planner.travel_acceleration, 100, 99000); - MENU_ITEM_EDIT_CALLBACK(float52, MSG_XSTEPS, &planner.axis_steps_per_mm[X_AXIS], 5, 9999, _planner_refresh_positioning); - MENU_ITEM_EDIT_CALLBACK(float52, MSG_YSTEPS, &planner.axis_steps_per_mm[Y_AXIS], 5, 9999, _planner_refresh_positioning); - #if ENABLED(DELTA) - MENU_ITEM_EDIT_CALLBACK(float52, MSG_ZSTEPS, &planner.axis_steps_per_mm[Z_AXIS], 5, 9999, _planner_refresh_positioning); + + // + // M92 Settings + // + MENU_ITEM_EDIT_CALLBACK(float62, MSG_XSTEPS, &planner.axis_steps_per_mm[X_AXIS], 5, 9999, _planner_refresh_positioning); + MENU_ITEM_EDIT_CALLBACK(float62, MSG_YSTEPS, &planner.axis_steps_per_mm[Y_AXIS], 5, 9999, _planner_refresh_positioning); + MENU_ITEM_EDIT_CALLBACK(float62, MSG_ZSTEPS, &planner.axis_steps_per_mm[Z_AXIS], 5, 9999, _planner_refresh_positioning); + + #if ENABLED(DISTINCT_E_FACTORS) + MENU_ITEM_EDIT_CALLBACK(float62, MSG_ESTEPS, &planner.axis_steps_per_mm[E_AXIS + active_extruder], 5, 9999, _planner_refresh_positioning); + MENU_ITEM_EDIT_CALLBACK(float62, MSG_ESTEPS MSG_E1, &planner.axis_steps_per_mm[E_AXIS], 5, 9999, _planner_refresh_e0_positioning); + MENU_ITEM_EDIT_CALLBACK(float62, MSG_ESTEPS MSG_E2, &planner.axis_steps_per_mm[E_AXIS + 1], 5, 9999, _planner_refresh_e1_positioning); + #if E_STEPPERS > 2 + MENU_ITEM_EDIT_CALLBACK(float62, MSG_ESTEPS MSG_E3, &planner.axis_steps_per_mm[E_AXIS + 2], 5, 9999, _planner_refresh_e2_positioning); + #if E_STEPPERS > 3 + MENU_ITEM_EDIT_CALLBACK(float62, MSG_ESTEPS MSG_E4, &planner.axis_steps_per_mm[E_AXIS + 3], 5, 9999, _planner_refresh_e3_positioning); + #endif + #endif #else - MENU_ITEM_EDIT_CALLBACK(float51, MSG_ZSTEPS, &planner.axis_steps_per_mm[Z_AXIS], 5, 9999, _planner_refresh_positioning); + MENU_ITEM_EDIT_CALLBACK(float62, MSG_ESTEPS, &planner.axis_steps_per_mm[E_AXIS], 5, 9999, _planner_refresh_positioning); #endif - MENU_ITEM_EDIT_CALLBACK(float51, MSG_ESTEPS, &planner.axis_steps_per_mm[E_AXIS], 5, 9999, _planner_refresh_positioning); + #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) MENU_ITEM_EDIT(bool, MSG_ENDSTOP_ABORT, &stepper.abort_on_endstop_hit); #endif - #if ENABLED(SCARA) - MENU_ITEM_EDIT(float74, MSG_XSCALE, &axis_scaling[X_AXIS], 0.5, 2); - MENU_ITEM_EDIT(float74, MSG_YSCALE, &axis_scaling[Y_AXIS], 0.5, 2); - #endif END_MENU(); } @@ -1809,9 +1985,9 @@ void kill_screen(const char* lcd_msg) { * "Control" > "Filament" submenu * */ - static void lcd_control_volumetric_menu() { + void lcd_control_volumetric_menu() { START_MENU(); - MENU_ITEM(back, MSG_CONTROL); + MENU_BACK(MSG_CONTROL); MENU_ITEM_EDIT_CALLBACK(bool, MSG_VOLUMETRIC_ENABLED, &volumetric_enabled, calculate_volumetric_multipliers); @@ -1839,8 +2015,8 @@ void kill_screen(const char* lcd_msg) { * */ #if HAS_LCD_CONTRAST - static void lcd_set_contrast() { - if (LCD_CLICKED) { lcd_goto_previous_menu(true); return; } + void lcd_set_contrast() { + if (lcd_clicked) { return lcd_goto_previous_menu(); } ENCODER_DIRECTION_NORMAL(); if (encoderPosition) { set_lcd_contrast(lcd_contrast + encoderPosition); @@ -1865,9 +2041,10 @@ void kill_screen(const char* lcd_msg) { * */ #if ENABLED(FWRETRACT) - static void lcd_control_retract_menu() { + + void lcd_control_retract_menu() { START_MENU(); - MENU_ITEM(back, MSG_CONTROL); + MENU_BACK(MSG_CONTROL); MENU_ITEM_EDIT(bool, MSG_AUTORETRACT, &autoretract_enabled); MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT, &retract_length, 0, 100); #if EXTRUDERS > 1 @@ -1882,20 +2059,23 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM_EDIT(float3, MSG_CONTROL_RETRACT_RECOVERF, &retract_recover_feedrate_mm_s, 1, 999); END_MENU(); } + #endif // FWRETRACT #if ENABLED(SDSUPPORT) #if !PIN_EXISTS(SD_DETECT) - static void lcd_sd_refresh() { + void lcd_sd_refresh() { card.initsd(); encoderTopLine = 0; } #endif - static void lcd_sd_updir() { + void lcd_sd_updir() { card.updir(); encoderTopLine = 0; + screen_changed = true; + lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; } /** @@ -1905,10 +2085,10 @@ void kill_screen(const char* lcd_msg) { */ void lcd_sdcard_menu() { ENCODER_DIRECTION_MENUS(); - if (lcdDrawUpdate == 0 && LCD_CLICKED == 0) return; // nothing to do (so don't thrash the SD card) + if (!lcdDrawUpdate && !lcd_clicked) return; // nothing to do (so don't thrash the SD card) uint16_t fileCnt = card.getnrfilenames(); START_MENU(); - MENU_ITEM(back, MSG_MAIN); + MENU_BACK(MSG_MAIN); card.getWorkDirName(); if (card.filename[0] == '/') { #if !PIN_EXISTS(SD_DETECT) @@ -1950,15 +2130,15 @@ void kill_screen(const char* lcd_msg) { * About Printer > Statistics submenu * */ - static void lcd_info_stats_menu() { - if (LCD_CLICKED) { lcd_goto_previous_menu(true); return; } + void lcd_info_stats_menu() { + if (lcd_clicked) { return lcd_goto_previous_menu(); } char buffer[21]; printStatistics stats = print_job_timer.getStats(); START_SCREEN(); // 12345678901234567890 STATIC_ITEM(MSG_INFO_PRINT_COUNT ": ", false, false, itostr3left(stats.totalPrints)); // Print Count: 999 - STATIC_ITEM(MSG_INFO_COMPLETED_PRINTS" : ", false, false, itostr3left(stats.finishedPrints)); // Completed : 666 + STATIC_ITEM(MSG_INFO_COMPLETED_PRINTS": ", false, false, itostr3left(stats.finishedPrints)); // Completed : 666 duration_t elapsed = stats.printTime; elapsed.toString(buffer); @@ -1972,7 +2152,7 @@ void kill_screen(const char* lcd_msg) { STATIC_ITEM(MSG_INFO_PRINT_LONGEST ": ", false, false); // Longest job time: STATIC_ITEM("", false, false, buffer); // 99y 364d 23h 59m 59s - sprintf_P(buffer, PSTR("%im"), stats.filamentUsed / 1000); + sprintf_P(buffer, PSTR("%ld.%im"), long(stats.filamentUsed / 1000), int(stats.filamentUsed / 100) % 10); STATIC_ITEM(MSG_INFO_PRINT_FILAMENT ": ", false, false); // Extruded total: STATIC_ITEM("", false, false, buffer); // 125m END_SCREEN(); @@ -1984,8 +2164,8 @@ void kill_screen(const char* lcd_msg) { * About Printer > Thermistors * */ - static void lcd_info_thermistors_menu() { - if (LCD_CLICKED) { lcd_goto_previous_menu(true); return; } + void lcd_info_thermistors_menu() { + if (lcd_clicked) { return lcd_goto_previous_menu(); } START_SCREEN(); #define THERMISTOR_ID TEMP_SENSOR_0 #include "thermistornames.h" @@ -2036,17 +2216,17 @@ void kill_screen(const char* lcd_msg) { * About Printer > Board Info * */ - static void lcd_info_board_menu() { - if (LCD_CLICKED) { lcd_goto_previous_menu(true); return; } + void lcd_info_board_menu() { + if (lcd_clicked) { return lcd_goto_previous_menu(); } START_SCREEN(); - STATIC_ITEM(BOARD_NAME, true, true); // MyPrinterController - STATIC_ITEM(MSG_INFO_BAUDRATE ": " STRINGIFY(BAUDRATE)); // Baud: 250000 - STATIC_ITEM(MSG_INFO_PROTOCOL ": " PROTOCOL_VERSION); // Protocol: 1.0 + STATIC_ITEM(BOARD_NAME, true, true); // MyPrinterController + STATIC_ITEM(MSG_INFO_BAUDRATE ": " STRINGIFY(BAUDRATE), true); // Baud: 250000 + STATIC_ITEM(MSG_INFO_PROTOCOL ": " PROTOCOL_VERSION, true); // Protocol: 1.0 #ifdef POWER_SUPPLY #if (POWER_SUPPLY == 1) - STATIC_ITEM(MSG_INFO_PSU ": ATX"); // Power Supply: ATX + STATIC_ITEM(MSG_INFO_PSU ": ATX", true); // Power Supply: ATX #elif (POWER_SUPPLY == 2) - STATIC_ITEM(MSG_INFO_PSU ": XBox"); // Power Supply: XBox + STATIC_ITEM(MSG_INFO_PSU ": XBox", true); // Power Supply: XBox #endif #endif // POWER_SUPPLY END_SCREEN(); @@ -2057,15 +2237,15 @@ void kill_screen(const char* lcd_msg) { * About Printer > Printer Info * */ - static void lcd_info_printer_menu() { - if (LCD_CLICKED) { lcd_goto_previous_menu(true); return; } + void lcd_info_printer_menu() { + if (lcd_clicked) { return lcd_goto_previous_menu(); } START_SCREEN(); - STATIC_ITEM(MSG_MARLIN, true, true); // Marlin - STATIC_ITEM(SHORT_BUILD_VERSION); // x.x.x-Branch - STATIC_ITEM(STRING_DISTRIBUTION_DATE); // YYYY-MM-DD HH:MM - STATIC_ITEM(MACHINE_NAME); // My3DPrinter - STATIC_ITEM(WEBSITE_URL); // www.my3dprinter.com - STATIC_ITEM(MSG_INFO_EXTRUDERS ": " STRINGIFY(EXTRUDERS)); // Extruders: 2 + STATIC_ITEM(MSG_MARLIN, true, true); // Marlin + STATIC_ITEM(SHORT_BUILD_VERSION, true); // x.x.x-Branch + STATIC_ITEM(STRING_DISTRIBUTION_DATE, true); // YYYY-MM-DD HH:MM + STATIC_ITEM(MACHINE_NAME, true); // My3DPrinter + STATIC_ITEM(WEBSITE_URL, true); // www.my3dprinter.com + STATIC_ITEM(MSG_INFO_EXTRUDERS ": " STRINGIFY(EXTRUDERS), true); // Extruders: 2 END_SCREEN(); } @@ -2074,9 +2254,9 @@ void kill_screen(const char* lcd_msg) { * "About Printer" submenu * */ - static void lcd_info_menu() { + void lcd_info_menu() { START_MENU(); - MENU_ITEM(back, MSG_MAIN); + MENU_BACK(MSG_MAIN); MENU_ITEM(submenu, MSG_INFO_PRINTER_MENU, lcd_info_printer_menu); // Printer Info > MENU_ITEM(submenu, MSG_INFO_BOARD_MENU, lcd_info_board_menu); // Board Info > MENU_ITEM(submenu, MSG_INFO_THERMISTOR_MENU, lcd_info_thermistors_menu); // Thermistors > @@ -2089,17 +2269,16 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(FILAMENT_CHANGE_FEATURE) - static void lcd_filament_change_resume_print() { + void lcd_filament_change_resume_print() { filament_change_menu_response = FILAMENT_CHANGE_RESPONSE_RESUME_PRINT; - lcdDrawUpdate = 2; lcd_goto_screen(lcd_status_screen); } - static void lcd_filament_change_extrude_more() { + void lcd_filament_change_extrude_more() { filament_change_menu_response = FILAMENT_CHANGE_RESPONSE_EXTRUDE_MORE; } - static void lcd_filament_change_option_menu() { + void lcd_filament_change_option_menu() { START_MENU(); #if LCD_HEIGHT > 2 STATIC_ITEM(MSG_FILAMENT_CHANGE_OPTION_HEADER, true, false); @@ -2109,7 +2288,7 @@ void kill_screen(const char* lcd_msg) { END_MENU(); } - static void lcd_filament_change_init_message() { + void lcd_filament_change_init_message() { START_SCREEN(); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_INIT_1); @@ -2122,7 +2301,7 @@ void kill_screen(const char* lcd_msg) { END_SCREEN(); } - static void lcd_filament_change_unload_message() { + void lcd_filament_change_unload_message() { START_SCREEN(); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_UNLOAD_1); @@ -2135,7 +2314,7 @@ void kill_screen(const char* lcd_msg) { END_SCREEN(); } - static void lcd_filament_change_insert_message() { + void lcd_filament_change_insert_message() { START_SCREEN(); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_INSERT_1); @@ -2148,7 +2327,7 @@ void kill_screen(const char* lcd_msg) { END_SCREEN(); } - static void lcd_filament_change_load_message() { + void lcd_filament_change_load_message() { START_SCREEN(); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_LOAD_1); @@ -2161,7 +2340,7 @@ void kill_screen(const char* lcd_msg) { END_SCREEN(); } - static void lcd_filament_change_extrude_message() { + void lcd_filament_change_extrude_message() { START_SCREEN(); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_EXTRUDE_1); @@ -2174,7 +2353,7 @@ void kill_screen(const char* lcd_msg) { END_SCREEN(); } - static void lcd_filament_change_resume_message() { + void lcd_filament_change_resume_message() { START_SCREEN(); STATIC_ITEM(MSG_FILAMENT_CHANGE_HEADER, true, true); STATIC_ITEM(MSG_FILAMENT_CHANGE_RESUME_1); @@ -2187,7 +2366,7 @@ void kill_screen(const char* lcd_msg) { END_SCREEN(); } - void lcd_filament_change_show_message(FilamentChangeMessage message) { + void lcd_filament_change_show_message(const FilamentChangeMessage message) { switch (message) { case FILAMENT_CHANGE_MESSAGE_INIT: defer_return_to_status = true; @@ -2231,9 +2410,9 @@ void kill_screen(const char* lcd_msg) { * bool _menu_edit_int3(); * void menu_edit_int3(); // edit int (interactively) * void menu_edit_callback_int3(); // edit int (interactively) with callback on completion - * static void _menu_action_setting_edit_int3(const char* pstr, int* ptr, int minValue, int maxValue); - * static void menu_action_setting_edit_int3(const char* pstr, int* ptr, int minValue, int maxValue); - * static void menu_action_setting_edit_callback_int3(const char* pstr, int* ptr, int minValue, int maxValue, screenFunc_t callback); // edit int with callback + * void _menu_action_setting_edit_int3(const char * const pstr, int * const ptr, const int minValue, const int maxValue); + * void menu_action_setting_edit_int3(const char * const pstr, int * const ptr, const int minValue, const int maxValue); + * void menu_action_setting_edit_callback_int3(const char * const pstr, int * const ptr, const int minValue, const int maxValue, const screenFunc_t callback); // edit int with callback * * You can then use one of the menu macros to present the edit interface: * MENU_ITEM_EDIT(int3, MSG_SPEED, &feedrate_percentage, 10, 999) @@ -2246,50 +2425,51 @@ void kill_screen(const char* lcd_msg) { * * menu_action_setting_edit_int3(PSTR(MSG_SPEED), &feedrate_percentage, 10, 999) */ - #define menu_edit_type(_type, _name, _strFunc, scale) \ + #define menu_edit_type(_type, _name, _strFunc, _scale) \ bool _menu_edit_ ## _name () { \ ENCODER_DIRECTION_NORMAL(); \ - bool isClicked = LCD_CLICKED; \ if ((int32_t)encoderPosition < 0) encoderPosition = 0; \ if ((int32_t)encoderPosition > maxEditValue) encoderPosition = maxEditValue; \ if (lcdDrawUpdate) \ - lcd_implementation_drawedit(editLabel, _strFunc(((_type)((int32_t)encoderPosition + minEditValue)) / scale)); \ - if (isClicked) { \ - *((_type*)editValue) = ((_type)((int32_t)encoderPosition + minEditValue)) / scale; \ - lcd_goto_previous_menu(true); \ + lcd_implementation_drawedit(editLabel, _strFunc(((_type)((int32_t)encoderPosition + minEditValue)) * (1.0 / _scale))); \ + if (lcd_clicked) { \ + *((_type*)editValue) = ((_type)((int32_t)encoderPosition + minEditValue)) * (1.0 / _scale); \ + lcd_goto_previous_menu(); \ } \ - return isClicked; \ + return lcd_clicked; \ } \ void menu_edit_ ## _name () { _menu_edit_ ## _name(); } \ void menu_edit_callback_ ## _name () { if (_menu_edit_ ## _name ()) (*callbackFunc)(); } \ - static void _menu_action_setting_edit_ ## _name (const char* pstr, _type* ptr, _type minValue, _type maxValue) { \ - lcd_save_previous_menu(); \ + void _menu_action_setting_edit_ ## _name (const char * const pstr, _type* const ptr, const _type minValue, const _type maxValue) { \ + lcd_save_previous_screen(); \ \ lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; \ \ editLabel = pstr; \ editValue = ptr; \ - minEditValue = minValue * scale; \ - maxEditValue = maxValue * scale - minEditValue; \ - encoderPosition = (*ptr) * scale - minEditValue; \ + minEditValue = minValue * _scale; \ + maxEditValue = maxValue * _scale - minEditValue; \ + encoderPosition = (*ptr) * _scale - minEditValue; \ } \ - static void menu_action_setting_edit_ ## _name (const char* pstr, _type* ptr, _type minValue, _type maxValue) { \ + void menu_action_setting_edit_ ## _name (const char * const pstr, _type * const ptr, const _type minValue, const _type maxValue) { \ _menu_action_setting_edit_ ## _name(pstr, ptr, minValue, maxValue); \ currentScreen = menu_edit_ ## _name; \ }\ - static void menu_action_setting_edit_callback_ ## _name (const char* pstr, _type* ptr, _type minValue, _type maxValue, screenFunc_t callback) { \ + void menu_action_setting_edit_callback_ ## _name (const char * const pstr, _type * const ptr, const _type minValue, const _type maxValue, const screenFunc_t callback) { \ _menu_action_setting_edit_ ## _name(pstr, ptr, minValue, maxValue); \ currentScreen = menu_edit_callback_ ## _name; \ callbackFunc = callback; \ - } + } \ + typedef void _name menu_edit_type(int, int3, itostr3, 1); - menu_edit_type(float, float3, ftostr3, 1); - menu_edit_type(float, float32, ftostr32, 100); - menu_edit_type(float, float43, ftostr43sign, 1000); + menu_edit_type(float, float3, ftostr3, 1.0); + menu_edit_type(float, float32, ftostr32, 100.0); + menu_edit_type(float, float43, ftostr43sign, 1000.0); menu_edit_type(float, float5, ftostr5rj, 0.01); - menu_edit_type(float, float51, ftostr51sign, 10); - menu_edit_type(float, float52, ftostr52sign, 100); + menu_edit_type(float, float51, ftostr51sign, 10.0); + menu_edit_type(float, float52, ftostr52sign, 100.0); + menu_edit_type(float, float62, ftostr62sign, 100.0); menu_edit_type(unsigned long, long5, ftostr5rj, 0.01); /** @@ -2298,23 +2478,24 @@ void kill_screen(const char* lcd_msg) { * */ #if ENABLED(REPRAPWORLD_KEYPAD) - static void _reprapworld_keypad_move(AxisEnum axis, int dir) { + void _reprapworld_keypad_move(AxisEnum axis, int dir) { move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP; encoderPosition = dir; switch (axis) { case X_AXIS: lcd_move_x(); break; case Y_AXIS: lcd_move_y(); break; case Z_AXIS: lcd_move_z(); + default: break; } } - static void reprapworld_keypad_move_z_up() { _reprapworld_keypad_move(Z_AXIS, 1); } - static void reprapworld_keypad_move_z_down() { _reprapworld_keypad_move(Z_AXIS, -1); } - static void reprapworld_keypad_move_x_left() { _reprapworld_keypad_move(X_AXIS, -1); } - static void reprapworld_keypad_move_x_right() { _reprapworld_keypad_move(X_AXIS, 1); } - static void reprapworld_keypad_move_y_up() { _reprapworld_keypad_move(Y_AXIS, -1); } - static void reprapworld_keypad_move_y_down() { _reprapworld_keypad_move(Y_AXIS, 1); } - static void reprapworld_keypad_move_home() { enqueue_and_echo_commands_P(PSTR("G28")); } // move all axes home and wait - static void reprapworld_keypad_move_menu() { lcd_goto_screen(lcd_move_menu); } + void reprapworld_keypad_move_z_up() { _reprapworld_keypad_move(Z_AXIS, 1); } + void reprapworld_keypad_move_z_down() { _reprapworld_keypad_move(Z_AXIS, -1); } + void reprapworld_keypad_move_x_left() { _reprapworld_keypad_move(X_AXIS, -1); } + void reprapworld_keypad_move_x_right() { _reprapworld_keypad_move(X_AXIS, 1); } + void reprapworld_keypad_move_y_up() { _reprapworld_keypad_move(Y_AXIS, -1); } + void reprapworld_keypad_move_y_down() { _reprapworld_keypad_move(Y_AXIS, 1); } + void reprapworld_keypad_move_home() { enqueue_and_echo_commands_P(PSTR("G28")); } // move all axes home and wait + void reprapworld_keypad_move_menu() { lcd_goto_screen(lcd_move_menu); } #endif // REPRAPWORLD_KEYPAD /** @@ -2327,11 +2508,14 @@ void kill_screen(const char* lcd_msg) { lcd.buzz(duration, freq); #elif PIN_EXISTS(BEEPER) buzzer.tone(duration, freq); + #else + UNUSED(duration); UNUSED(freq); #endif } void lcd_quick_feedback() { lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; + buttons = 0; next_button_update_ms = millis() + 500; // Buzz and wait. The delay is needed for buttons to settle! @@ -2348,39 +2532,44 @@ void kill_screen(const char* lcd_msg) { * Menu actions * */ - static void menu_action_back() { lcd_goto_previous_menu(); } - static void menu_action_submenu(screenFunc_t func) { lcd_save_previous_menu(); lcd_goto_screen(func); } - static void menu_action_gcode(const char* pgcode) { enqueue_and_echo_commands_P(pgcode); } - static void menu_action_function(screenFunc_t func) { (*func)(); } + void _menu_action_back() { lcd_goto_previous_menu(); } + void menu_action_submenu(screenFunc_t func) { lcd_save_previous_screen(); lcd_goto_screen(func); } + void menu_action_gcode(const char* pgcode) { enqueue_and_echo_commands_P(pgcode); } + void menu_action_function(screenFunc_t func) { (*func)(); } #if ENABLED(SDSUPPORT) - static void menu_action_sdfile(const char* filename, char* longFilename) { + void menu_action_sdfile(const char* filename, char* longFilename) { UNUSED(longFilename); card.openAndPrintFile(filename); lcd_return_to_status(); } - static void menu_action_sddirectory(const char* filename, char* longFilename) { + void menu_action_sddirectory(const char* filename, char* longFilename) { UNUSED(longFilename); card.chdir(filename); encoderPosition = 0; + screen_changed = true; + lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; } #endif //SDSUPPORT - static void menu_action_setting_edit_bool(const char* pstr, bool* ptr) {UNUSED(pstr); *ptr = !(*ptr); } - static void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr, screenFunc_t callback) { + void menu_action_setting_edit_bool(const char* pstr, bool* ptr) {UNUSED(pstr); *ptr = !(*ptr); } + void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr, screenFunc_t callback) { menu_action_setting_edit_bool(pstr, ptr); (*callback)(); } -#endif //ULTIPANEL +#endif // ULTIPANEL -/** LCD API **/ void lcd_init() { - lcd_implementation_init(); + lcd_implementation_init( + #if ENABLED(LCD_PROGRESS_BAR) + true + #endif + ); #if ENABLED(NEWPANEL) #if BUTTON_EXISTS(EN1) @@ -2399,11 +2588,9 @@ void lcd_init() { #endif #if ENABLED(REPRAPWORLD_KEYPAD) - pinMode(SHIFT_CLK, OUTPUT); - pinMode(SHIFT_LD, OUTPUT); - pinMode(SHIFT_OUT, INPUT); - WRITE(SHIFT_OUT, HIGH); - WRITE(SHIFT_LD, HIGH); + SET_OUTPUT(SHIFT_CLK); + OUT_WRITE(SHIFT_LD, HIGH); + SET_INPUT_PULLUP(SHIFT_OUT); #endif #if BUTTON_EXISTS(UP) @@ -2422,16 +2609,13 @@ void lcd_init() { #else // !NEWPANEL #if ENABLED(SR_LCD_2W_NL) // Non latching 2 wire shift register - pinMode(SR_DATA_PIN, OUTPUT); - pinMode(SR_CLK_PIN, OUTPUT); + SET_OUTPUT(SR_DATA_PIN); + SET_OUTPUT(SR_CLK_PIN); #elif defined(SHIFT_CLK) - pinMode(SHIFT_CLK, OUTPUT); - pinMode(SHIFT_LD, OUTPUT); - pinMode(SHIFT_EN, OUTPUT); - pinMode(SHIFT_OUT, INPUT); - WRITE(SHIFT_OUT, HIGH); - WRITE(SHIFT_LD, HIGH); - WRITE(SHIFT_EN, LOW); + SET_OUTPUT(SHIFT_CLK); + OUT_WRITE(SHIFT_LD, HIGH); + OUT_WRITE(SHIFT_EN, LOW); + SET_INPUT_PULLUP(SHIFT_OUT); #endif // SR_LCD_2W_NL #endif // !NEWPANEL @@ -2527,20 +2711,25 @@ void lcd_update() { #if ENABLED(ULTIPANEL) static millis_t return_to_status_ms = 0; manage_manual_move(); - #endif - lcd_buttons_update(); + lcd_buttons_update(); + + // If the action button is pressed... + if (LCD_CLICKED) { + if (!wait_for_unclick) { // If not waiting for a debounce release: + wait_for_unclick = true; // Set debounce flag to ignore continous clicks + lcd_clicked = !wait_for_user; // Keep the click if not waiting for a user-click + wait_for_user = false; // Any click clears wait for user + lcd_quick_feedback(); // Always make a click sound + } + } + else wait_for_unclick = false; + #endif #if ENABLED(SDSUPPORT) && PIN_EXISTS(SD_DETECT) bool sd_status = IS_SD_INSERTED; if (sd_status != lcd_sd_status && lcd_detected()) { - lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; - lcd_implementation_init( // to maybe revive the LCD if static electricity killed it. - #if ENABLED(LCD_PROGRESS_BAR) && ENABLED(ULTIPANEL) - currentScreen == lcd_status_screen - #endif - ); if (sd_status) { card.initsd(); @@ -2552,6 +2741,12 @@ void lcd_update() { } lcd_sd_status = sd_status; + lcdDrawUpdate = LCDVIEW_CLEAR_CALL_REDRAW; + lcd_implementation_init( // to maybe revive the LCD if static electricity killed it. + #if ENABLED(LCD_PROGRESS_BAR) + currentScreen == lcd_status_screen + #endif + ); } #endif //SDSUPPORT && SD_DETECT_PIN @@ -2565,12 +2760,12 @@ void lcd_update() { lcd_implementation_update_indicators(); #endif - #if ENABLED(LCD_HAS_SLOW_BUTTONS) - slow_buttons = lcd_implementation_read_slow_buttons(); // buttons which take too long to read in interrupt context - #endif - #if ENABLED(ULTIPANEL) + #if ENABLED(LCD_HAS_SLOW_BUTTONS) + slow_buttons = lcd_implementation_read_slow_buttons(); // buttons which take too long to read in interrupt context + #endif + #if ENABLED(REPRAPWORLD_KEYPAD) static uint8_t keypad_debounce = 0; @@ -2604,7 +2799,7 @@ void lcd_update() { #endif // REPRAPWORLD_KEYPAD bool encoderPastThreshold = (abs(encoderDiff) >= ENCODER_PULSES_PER_STEP); - if (encoderPastThreshold || LCD_CLICKED) { + if (encoderPastThreshold || lcd_clicked) { if (encoderPastThreshold) { int32_t encoderMultiplier = 1; @@ -2643,73 +2838,93 @@ void lcd_update() { } #endif // ULTIPANEL + #if ENABLED(ENSURE_SMOOTH_MOVES) && ENABLED(ALWAYS_ALLOW_MENU) + #define STATUS_UPDATE_CONDITION planner.long_move() + #else + #define STATUS_UPDATE_CONDITION true + #endif + #if ENABLED(ENSURE_SMOOTH_MOVES) && DISABLED(ALWAYS_ALLOW_MENU) + #define LCD_HANDLER_CONDITION planner.long_move() + #else + #define LCD_HANDLER_CONDITION true + #endif + // We arrive here every ~100ms when idling often enough. // Instead of tracking the changes simply redraw the Info Screen ~1 time a second. static int8_t lcd_status_update_delay = 1; // first update one loop delayed - if ( + if (STATUS_UPDATE_CONDITION && #if ENABLED(ULTIPANEL) currentScreen == lcd_status_screen && #endif - !lcd_status_update_delay--) { + !lcd_status_update_delay-- + ) { lcd_status_update_delay = 9; lcdDrawUpdate = LCDVIEW_REDRAW_NOW; } - if (lcdDrawUpdate) { + if (LCD_HANDLER_CONDITION) { - switch (lcdDrawUpdate) { - case LCDVIEW_CALL_NO_REDRAW: - lcdDrawUpdate = LCDVIEW_NONE; - break; - case LCDVIEW_CLEAR_CALL_REDRAW: // set by handlers, then altered after (rarely occurs here) - case LCDVIEW_CALL_REDRAW_NEXT: // set by handlers, then altered after (never occurs here?) - lcdDrawUpdate = LCDVIEW_REDRAW_NOW; - case LCDVIEW_REDRAW_NOW: // set above, or by a handler through LCDVIEW_CALL_REDRAW_NEXT - case LCDVIEW_NONE: - break; + if (lcdDrawUpdate) { + + switch (lcdDrawUpdate) { + case LCDVIEW_CALL_NO_REDRAW: + lcdDrawUpdate = LCDVIEW_NONE; + break; + case LCDVIEW_CLEAR_CALL_REDRAW: // set by handlers, then altered after (rarely occurs here) + case LCDVIEW_CALL_REDRAW_NEXT: // set by handlers, then altered after (never occurs here?) + lcdDrawUpdate = LCDVIEW_REDRAW_NOW; + case LCDVIEW_REDRAW_NOW: // set above, or by a handler through LCDVIEW_CALL_REDRAW_NEXT + case LCDVIEW_NONE: + break; + } // switch + + #if ENABLED(ULTIPANEL) + #define CURRENTSCREEN() (*currentScreen)(), lcd_clicked = false + #else + #define CURRENTSCREEN() lcd_status_screen() + #endif + + #if ENABLED(DOGLCD) // Changes due to different driver architecture of the DOGM display + static int8_t dot_color = 0; + dot_color = 1 - dot_color; + u8g.firstPage(); + do { + lcd_setFont(FONT_MENU); + u8g.setPrintPos(125, 0); + u8g.setColorIndex(dot_color); // Set color for the alive dot + u8g.drawPixel(127, 63); // draw alive dot + u8g.setColorIndex(1); // black on white + CURRENTSCREEN(); + } while (u8g.nextPage()); + #else + CURRENTSCREEN(); + #endif } - #if ENABLED(DOGLCD) // Changes due to different driver architecture of the DOGM display - static int8_t dot_color = 0; - dot_color = 1 - dot_color; - u8g.firstPage(); - do { - lcd_setFont(FONT_MENU); - u8g.setPrintPos(125, 0); - u8g.setColorIndex(dot_color); // Set color for the alive dot - u8g.drawPixel(127, 63); // draw alive dot - u8g.setColorIndex(1); // black on white - (*currentScreen)(); - } while (u8g.nextPage()); - #elif ENABLED(ULTIPANEL) - (*currentScreen)(); - #else - lcd_status_screen(); - #endif - } + #if ENABLED(ULTIPANEL) - #if ENABLED(ULTIPANEL) + // Return to Status Screen after a timeout + if (currentScreen == lcd_status_screen || defer_return_to_status) + return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS; + else if (ELAPSED(ms, return_to_status_ms)) + lcd_return_to_status(); - // Return to Status Screen after a timeout - if (currentScreen == lcd_status_screen || defer_return_to_status) - return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS; - else if (ELAPSED(ms, return_to_status_ms)) - lcd_return_to_status(); + #endif // ULTIPANEL - #endif // ULTIPANEL + switch (lcdDrawUpdate) { + case LCDVIEW_CLEAR_CALL_REDRAW: + lcd_implementation_clear(); + case LCDVIEW_CALL_REDRAW_NEXT: + lcdDrawUpdate = LCDVIEW_REDRAW_NOW; + break; + case LCDVIEW_REDRAW_NOW: + lcdDrawUpdate = LCDVIEW_NONE; + break; + case LCDVIEW_NONE: + break; + } // switch - switch (lcdDrawUpdate) { - case LCDVIEW_CLEAR_CALL_REDRAW: - lcd_implementation_clear(); - case LCDVIEW_CALL_REDRAW_NEXT: - lcdDrawUpdate = LCDVIEW_REDRAW_NOW; - break; - case LCDVIEW_REDRAW_NOW: - lcdDrawUpdate = LCDVIEW_NONE; - break; - case LCDVIEW_NONE: - break; - } + } // LCD_HANDLER_CONDITION } } @@ -2753,20 +2968,20 @@ void lcd_finishstatus(bool persist=false) { bool lcd_hasstatus() { return (lcd_status_message[0] != '\0'); } -void lcd_setstatus(const char* message, bool persist) { +void lcd_setstatus(const char* const message, bool persist) { if (lcd_status_message_level > 0) return; strncpy(lcd_status_message, message, 3 * (LCD_WIDTH)); lcd_finishstatus(persist); } -void lcd_setstatuspgm(const char* message, uint8_t level) { +void lcd_setstatuspgm(const char* const message, uint8_t level) { if (level < lcd_status_message_level) return; lcd_status_message_level = level; strncpy_P(lcd_status_message, message, 3 * (LCD_WIDTH)); lcd_finishstatus(level > 0); } -void lcd_setalertstatuspgm(const char* message) { +void lcd_setalertstatuspgm(const char* const message) { lcd_setstatuspgm(message, 1); #if ENABLED(ULTIPANEL) lcd_return_to_status(); @@ -2776,7 +2991,7 @@ void lcd_setalertstatuspgm(const char* message) { void lcd_reset_alert_level() { lcd_status_message_level = 0; } #if HAS_LCD_CONTRAST - void set_lcd_contrast(int value) { + void set_lcd_contrast(const int value) { lcd_contrast = constrain(value, LCD_CONTRAST_MIN, LCD_CONTRAST_MAX); u8g.setContrast(lcd_contrast); } @@ -2814,64 +3029,82 @@ void lcd_reset_alert_level() { lcd_status_message_level = 0; } * Warning: This function is called from interrupt context! */ void lcd_buttons_update() { - #if ENABLED(NEWPANEL) - uint8_t newbutton = 0; - #if BUTTON_EXISTS(EN1) - if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; - #endif - #if BUTTON_EXISTS(EN2) - if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; - #endif - #if LCD_HAS_DIRECTIONAL_BUTTONS || BUTTON_EXISTS(ENC) - millis_t now = millis(); - #endif + millis_t now = millis(); + if (ELAPSED(now, next_button_update_ms)) { + + #if ENABLED(NEWPANEL) + uint8_t newbutton = 0; + + #if BUTTON_EXISTS(EN1) + if (BUTTON_PRESSED(EN1)) newbutton |= EN_A; + #endif + + #if BUTTON_EXISTS(EN2) + if (BUTTON_PRESSED(EN2)) newbutton |= EN_B; + #endif + + #if BUTTON_EXISTS(ENC) + if (BUTTON_PRESSED(ENC)) newbutton |= EN_C; + #endif + + #if LCD_HAS_DIRECTIONAL_BUTTONS + + // Manage directional buttons + #if ENABLED(REVERSE_MENU_DIRECTION) + #define _ENCODER_UD_STEPS (ENCODER_STEPS_PER_MENU_ITEM * encoderDirection) + #else + #define _ENCODER_UD_STEPS ENCODER_STEPS_PER_MENU_ITEM + #endif + #if ENABLED(REVERSE_ENCODER_DIRECTION) + #define ENCODER_UD_STEPS _ENCODER_UD_STEPS + #define ENCODER_LR_PULSES ENCODER_PULSES_PER_STEP + #else + #define ENCODER_UD_STEPS -(_ENCODER_UD_STEPS) + #define ENCODER_LR_PULSES -(ENCODER_PULSES_PER_STEP) + #endif - #if LCD_HAS_DIRECTIONAL_BUTTONS - if (ELAPSED(now, next_button_update_ms)) { if (false) { // for the else-ifs below } #if BUTTON_EXISTS(UP) else if (BUTTON_PRESSED(UP)) { - encoderDiff = -(ENCODER_STEPS_PER_MENU_ITEM); + encoderDiff = -(ENCODER_UD_STEPS); next_button_update_ms = now + 300; } #endif #if BUTTON_EXISTS(DWN) else if (BUTTON_PRESSED(DWN)) { - encoderDiff = ENCODER_STEPS_PER_MENU_ITEM; + encoderDiff = ENCODER_UD_STEPS; next_button_update_ms = now + 300; } #endif #if BUTTON_EXISTS(LFT) else if (BUTTON_PRESSED(LFT)) { - encoderDiff = -(ENCODER_PULSES_PER_STEP); + encoderDiff = -(ENCODER_LR_PULSES); next_button_update_ms = now + 300; } #endif #if BUTTON_EXISTS(RT) else if (BUTTON_PRESSED(RT)) { - encoderDiff = ENCODER_PULSES_PER_STEP; + encoderDiff = ENCODER_LR_PULSES; next_button_update_ms = now + 300; } #endif - } - #endif - #if BUTTON_EXISTS(ENC) - if (ELAPSED(now, next_button_update_ms) && BUTTON_PRESSED(ENC)) newbutton |= EN_C; - #endif + #endif // LCD_HAS_DIRECTIONAL_BUTTONS - buttons = newbutton; - #if ENABLED(LCD_HAS_SLOW_BUTTONS) - buttons |= slow_buttons; - #endif - #if ENABLED(REPRAPWORLD_KEYPAD) - GET_BUTTON_STATES(buttons_reprapworld_keypad); - #endif - #else - GET_BUTTON_STATES(buttons); - #endif //!NEWPANEL + buttons = newbutton; + #if ENABLED(LCD_HAS_SLOW_BUTTONS) + buttons |= slow_buttons; + #endif + #if ENABLED(REPRAPWORLD_KEYPAD) + GET_BUTTON_STATES(buttons_reprapworld_keypad); + #endif + #else + GET_BUTTON_STATES(buttons); + #endif //!NEWPANEL + + } // next_button_update_ms // Manage encoder rotation #if ENABLED(REVERSE_MENU_DIRECTION) && ENABLED(REVERSE_ENCODER_DIRECTION) @@ -2903,264 +3136,10 @@ void lcd_reset_alert_level() { lcd_status_message_level = 0; } lastEncoderBits = enc; } - bool lcd_detected(void) { - #if (ENABLED(LCD_I2C_TYPE_MCP23017) || ENABLED(LCD_I2C_TYPE_MCP23008)) && ENABLED(DETECT_DEVICE) - return lcd.LcdDetected() == 1; - #else - return true; - #endif - } - - bool lcd_clicked() { return LCD_CLICKED; } + #if (ENABLED(LCD_I2C_TYPE_MCP23017) || ENABLED(LCD_I2C_TYPE_MCP23008)) && ENABLED(DETECT_DEVICE) + bool lcd_detected() { return lcd.LcdDetected() == 1; } + #endif #endif // ULTIPANEL -/*********************************/ -/** Number to string conversion **/ -/*********************************/ - -#define DIGIT(n) ('0' + (n)) -#define DIGIMOD(n) DIGIT((n) % 10) - -char conv[8]; - -// Convert float to rj string with 123 or -12 format -char *ftostr3(const float& x) { return itostr3((int)x); } - -// Convert float to rj string with _123, -123, _-12, or __-1 format -char *ftostr4sign(const float& x) { return itostr4sign((int)x); } - -// Convert unsigned int to string with 12 format -char* itostr2(const uint8_t& x) { - int xx = x; - conv[0] = DIGIMOD(xx / 10); - conv[1] = DIGIMOD(xx); - conv[2] = '\0'; - return conv; -} - -// Convert float to string with +123.4 / -123.4 format -char* ftostr41sign(const float& x) { - int xx = int(abs(x * 10)) % 10000; - conv[0] = x >= 0 ? '+' : '-'; - conv[1] = DIGIMOD(xx / 1000); - conv[2] = DIGIMOD(xx / 100); - conv[3] = DIGIMOD(xx / 10); - conv[4] = '.'; - conv[5] = DIGIMOD(xx); - conv[6] = '\0'; - return conv; -} - -// Convert signed float to string with 023.45 / -23.45 format -char *ftostr32(const float& x) { - long xx = abs(x * 100); - conv[0] = x >= 0 ? DIGIMOD(xx / 10000) : '-'; - conv[1] = DIGIMOD(xx / 1000); - conv[2] = DIGIMOD(xx / 100); - conv[3] = '.'; - conv[4] = DIGIMOD(xx / 10); - conv[5] = DIGIMOD(xx); - conv[6] = '\0'; - return conv; -} - -// Convert signed float to string (6 digit) with -1.234 / _0.000 / +1.234 format -char* ftostr43sign(const float& x, char plus/*=' '*/) { - long xx = x * 1000; - if (xx == 0) - conv[0] = ' '; - else if (xx > 0) - conv[0] = plus; - else { - xx = -xx; - conv[0] = '-'; - } - conv[1] = DIGIMOD(xx / 1000); - conv[2] = '.'; - conv[3] = DIGIMOD(xx / 100); - conv[4] = DIGIMOD(xx / 10); - conv[5] = DIGIMOD(xx); - conv[6] = '\0'; - return conv; -} - -// Convert unsigned float to string with 1.23 format -char* ftostr12ns(const float& x) { - long xx = x * 100; - xx = abs(xx); - conv[0] = DIGIMOD(xx / 100); - conv[1] = '.'; - conv[2] = DIGIMOD(xx / 10); - conv[3] = DIGIMOD(xx); - conv[4] = '\0'; - return conv; -} - -// Convert signed int to lj string with +012 / -012 format -char* itostr3sign(const int& x) { - int xx; - if (x >= 0) { - conv[0] = '+'; - xx = x; - } - else { - conv[0] = '-'; - xx = -x; - } - conv[1] = DIGIMOD(xx / 100); - conv[2] = DIGIMOD(xx / 10); - conv[3] = DIGIMOD(xx); - conv[4] = '.'; - conv[5] = '0'; - conv[6] = '\0'; - return conv; -} - -// Convert signed int to rj string with 123 or -12 format -char* itostr3(const int& x) { - int xx = x; - if (xx < 0) { - conv[0] = '-'; - xx = -xx; - } - else - conv[0] = xx >= 100 ? DIGIMOD(xx / 100) : ' '; - - conv[1] = xx >= 10 ? DIGIMOD(xx / 10) : ' '; - conv[2] = DIGIMOD(xx); - conv[3] = '\0'; - return conv; -} - -// Convert unsigned int to lj string with 123 format -char* itostr3left(const int& xx) { - if (xx >= 100) { - conv[0] = DIGIMOD(xx / 100); - conv[1] = DIGIMOD(xx / 10); - conv[2] = DIGIMOD(xx); - conv[3] = '\0'; - } - else if (xx >= 10) { - conv[0] = DIGIMOD(xx / 10); - conv[1] = DIGIMOD(xx); - conv[2] = '\0'; - } - else { - conv[0] = DIGIMOD(xx); - conv[1] = '\0'; - } - return conv; -} - -// Convert signed int to rj string with _123, -123, _-12, or __-1 format -char *itostr4sign(const int& x) { - int xx = abs(x); - int sign = 0; - if (xx >= 100) { - conv[1] = DIGIMOD(xx / 100); - conv[2] = DIGIMOD(xx / 10); - } - else if (xx >= 10) { - conv[0] = ' '; - sign = 1; - conv[2] = DIGIMOD(xx / 10); - } - else { - conv[0] = ' '; - conv[1] = ' '; - sign = 2; - } - conv[sign] = x < 0 ? '-' : ' '; - conv[3] = DIGIMOD(xx); - conv[4] = '\0'; - return conv; -} - -// Convert unsigned float to rj string with 12345 format -char* ftostr5rj(const float& x) { - long xx = abs(x); - conv[0] = xx >= 10000 ? DIGIMOD(xx / 10000) : ' '; - conv[1] = xx >= 1000 ? DIGIMOD(xx / 1000) : ' '; - conv[2] = xx >= 100 ? DIGIMOD(xx / 100) : ' '; - conv[3] = xx >= 10 ? DIGIMOD(xx / 10) : ' '; - conv[4] = DIGIMOD(xx); - conv[5] = '\0'; - return conv; -} - -// Convert signed float to string with +1234.5 format -char* ftostr51sign(const float& x) { - long xx = abs(x * 10); - conv[0] = (x >= 0) ? '+' : '-'; - conv[1] = DIGIMOD(xx / 10000); - conv[2] = DIGIMOD(xx / 1000); - conv[3] = DIGIMOD(xx / 100); - conv[4] = DIGIMOD(xx / 10); - conv[5] = '.'; - conv[6] = DIGIMOD(xx); - conv[7] = '\0'; - return conv; -} - -// Convert signed float to string with +123.45 format -char* ftostr52sign(const float& x) { - long xx = abs(x * 100); - conv[0] = (x >= 0) ? '+' : '-'; - conv[1] = DIGIMOD(xx / 10000); - conv[2] = DIGIMOD(xx / 1000); - conv[3] = DIGIMOD(xx / 100); - conv[4] = '.'; - conv[5] = DIGIMOD(xx / 10); - conv[6] = DIGIMOD(xx); - conv[7] = '\0'; - return conv; -} - -// Convert signed float to space-padded string with -_23.4_ format -char* ftostr52sp(const float& x) { - long xx = x * 100; - uint8_t dig; - if (xx < 0) { // negative val = -_0 - xx = -xx; - conv[0] = '-'; - dig = (xx / 1000) % 10; - conv[1] = dig ? DIGIT(dig) : ' '; - } - else { // positive val = __0 - dig = (xx / 10000) % 10; - if (dig) { - conv[0] = DIGIT(dig); - conv[1] = DIGIMOD(xx / 1000); - } - else { - conv[0] = ' '; - dig = (xx / 1000) % 10; - conv[1] = dig ? DIGIT(dig) : ' '; - } - } - - conv[2] = DIGIMOD(xx / 100); // lsd always - - dig = xx % 10; - if (dig) { // 2 decimal places - conv[5] = DIGIT(dig); - conv[4] = DIGIMOD(xx / 10); - conv[3] = '.'; - } - else { // 1 or 0 decimal place - dig = (xx / 10) % 10; - if (dig) { - conv[4] = DIGIT(dig); - conv[3] = '.'; - } - else { - conv[3] = conv[4] = ' '; - } - conv[5] = ' '; - } - conv[6] = '\0'; - return conv; -} - #endif // ULTRA_LCD diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index 4cc8334ec9..f0d0a42844 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -30,6 +30,8 @@ #define BUTTON_EXISTS(BN) (defined(BTN_## BN) && BTN_## BN >= 0) #define BUTTON_PRESSED(BN) !READ(BTN_## BN) + extern int lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2]; + int lcd_strlen(const char* s); int lcd_strlen_P(const char* s); void lcd_update(); @@ -39,10 +41,15 @@ void lcd_setstatuspgm(const char* message, const uint8_t level=0); void lcd_setalertstatuspgm(const char* message); void lcd_reset_alert_level(); - bool lcd_detected(void); void lcd_kill_screen(); void kill_screen(const char* lcd_msg); + #if (ENABLED(LCD_I2C_TYPE_MCP23017) || ENABLED(LCD_I2C_TYPE_MCP23008)) && ENABLED(DETECT_DEVICE) + bool lcd_detected(); + #else + inline bool lcd_detected() { return true; } + #endif + #if HAS_BUZZER void lcd_buzz(long duration, uint16_t freq); #endif @@ -65,26 +72,30 @@ #define LCD_TIMEOUT_TO_STATUS 15000 #if ENABLED(ULTIPANEL) + + #define BLEN_A 0 + #define BLEN_B 1 + // Encoder click is directly connected + #if BUTTON_EXISTS(ENC) + #define BLEN_C 2 + #endif + #define EN_A (_BV(BLEN_A)) + #define EN_B (_BV(BLEN_B)) + #define EN_C (_BV(BLEN_C)) + extern volatile uint8_t buttons; //the last checked buttons in a bit array. void lcd_buttons_update(); void lcd_quick_feedback(); // Audible feedback for a button click - could also be visual - bool lcd_clicked(); - void lcd_ignore_click(bool b=true); #if ENABLED(FILAMENT_CHANGE_FEATURE) - void lcd_filament_change_show_message(FilamentChangeMessage message); + void lcd_filament_change_show_message(const FilamentChangeMessage message); #endif // FILAMENT_CHANGE_FEATURE #else - FORCE_INLINE void lcd_buttons_update() {} - #endif - extern int preheatHotendTemp1; - extern int preheatBedTemp1; - extern int preheatFanSpeed1; - extern int preheatHotendTemp2; - extern int preheatBedTemp2; - extern int preheatFanSpeed2; + inline void lcd_buttons_update() {} + + #endif #if ENABLED(FILAMENT_LCD_DISPLAY) extern millis_t previous_lcd_status_ms; @@ -92,19 +103,6 @@ bool lcd_blink(); - #if ENABLED(ULTIPANEL) - #define BLEN_A 0 - #define BLEN_B 1 - // Encoder click is directly connected - #if BUTTON_EXISTS(ENC) - #define BLEN_C 2 - #define EN_C (_BV(BLEN_C)) - #endif - #define EN_A (_BV(BLEN_A)) - #define EN_B (_BV(BLEN_B)) - #define EN_C (_BV(BLEN_C)) - #endif - #if ENABLED(REPRAPWORLD_KEYPAD) // is also ULTIPANEL and NEWPANEL #define REPRAPWORLD_BTN_OFFSET 0 // bit offset into buttons for shift register values @@ -150,38 +148,23 @@ #define LCD_CLICKED ((buttons & EN_C) || (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_F1)) #elif ENABLED(NEWPANEL) #define LCD_CLICKED (buttons & EN_C) + #else + #define LCD_CLICKED false #endif #else //no LCD - FORCE_INLINE void lcd_update() {} - FORCE_INLINE void lcd_init() {} - FORCE_INLINE bool lcd_hasstatus() { return false; } - FORCE_INLINE void lcd_setstatus(const char* message, const bool persist=false) {UNUSED(message); UNUSED(persist);} - FORCE_INLINE void lcd_setstatuspgm(const char* message, const uint8_t level=0) {UNUSED(message); UNUSED(level);} - FORCE_INLINE void lcd_buttons_update() {} - FORCE_INLINE void lcd_reset_alert_level() {} - FORCE_INLINE bool lcd_detected(void) { return true; } + inline void lcd_update() {} + inline void lcd_init() {} + inline bool lcd_hasstatus() { return false; } + inline void lcd_setstatus(const char* const message, const bool persist=false) { UNUSED(message); UNUSED(persist); } + inline void lcd_setstatuspgm(const char* const message, const uint8_t level=0) { UNUSED(message); UNUSED(level); } + inline void lcd_buttons_update() {} + inline void lcd_reset_alert_level() {} + inline bool lcd_detected() { return true; } #define LCD_MESSAGEPGM(x) NOOP #define LCD_ALERTMESSAGEPGM(x) NOOP -#endif //ULTRA_LCD +#endif // ULTRA_LCD -char* itostr2(const uint8_t& x); -char* itostr3sign(const int& x); -char* itostr3(const int& x); -char* itostr3left(const int& x); -char* itostr4sign(const int& x); - -char* ftostr3(const float& x); -char* ftostr4sign(const float& x); -char* ftostr41sign(const float& x); -char* ftostr32(const float& x); -char* ftostr43sign(const float& x, char plus=' '); -char* ftostr12ns(const float& x); -char* ftostr5rj(const float& x); -char* ftostr51sign(const float& x); -char* ftostr52sign(const float& x); -char* ftostr52sp(const float& x); // remove zero-padding from ftostr32 - -#endif //ULTRALCD_H +#endif // ULTRALCD_H diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index f8ffd4db00..46a5225618 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -45,6 +45,7 @@ #include "ultralcd.h" #include "ultralcd_st7920_u8glib_rrd.h" #include "dogm_bitmaps.h" +#include "utility.h" #include "duration_t.h" #include @@ -53,8 +54,10 @@ #include "_Bootscreen.h" #endif -#if DISABLED(MAPPER_C2C3) && DISABLED(MAPPER_NON) && ENABLED(USE_BIG_EDIT_FONT) +// Only Western languages support big / small fonts +#if DISABLED(DISPLAY_CHARSET_ISO10646_1) #undef USE_BIG_EDIT_FONT + #undef USE_SMALL_INFOFONT #endif #if ENABLED(USE_SMALL_INFOFONT) @@ -84,6 +87,9 @@ #include "dogm_font_data_ISO10646_CN.h" #define FONT_MENU_NAME ISO10646_CN #define TALL_FONT_CORRECTION 1 + #elif ENABLED(DISPLAY_CHARSET_ISO10646_TR) + #include "dogm_font_data_ISO10646_1_tr.h" + #define FONT_MENU_NAME ISO10646_TR #else // fall-back #include "dogm_font_data_ISO10646_1.h" #define FONT_MENU_NAME ISO10646_1_5x7 @@ -117,7 +123,7 @@ #if ENABLED(USE_BIG_EDIT_FONT) #define FONT_MENU_EDIT_NAME u8g_font_9x18 #define DOG_CHAR_WIDTH_EDIT 9 - #define DOG_CHAR_HEIGHT_EDIT 18 + #define DOG_CHAR_HEIGHT_EDIT 13 #define LCD_WIDTH_EDIT 14 #else #define FONT_MENU_EDIT_NAME FONT_MENU_NAME @@ -134,36 +140,47 @@ // LCD selection #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - U8GLIB_ST7920_128X64_4X u8g(LCD_PINS_RS); + U8GLIB_ST7920_128X64_4X u8g(LCD_PINS_RS); // 2 stripes + // U8GLIB_ST7920_128X64 u8g(LCD_PINS_RS); // 8 stripes #elif ENABLED(U8GLIB_ST7920) - //U8GLIB_ST7920_128X64_RRD u8g(0,0,0); - U8GLIB_ST7920_128X64_RRD u8g(0); + //U8GLIB_ST7920_128X64_4X u8g(LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS); // Original u8glib device. 2 stripes + // No 4 stripe device available from u8glib. + //U8GLIB_ST7920_128X64 u8g(LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS); // Original u8glib device. 8 stripes + U8GLIB_ST7920_128X64_RRD u8g(0); // Number of stripes can be adjusted in ultralcd_st7920_u8glib_rrd.h with PAGE_HEIGHT #elif ENABLED(CARTESIO_UI) // The CartesioUI display #if DOGLCD_MOSI != -1 && DOGLCD_SCK != -1 // using SW-SPI - U8GLIB_DOGM128 u8g(DOGLCD_SCK, DOGLCD_MOSI, DOGLCD_CS, DOGLCD_A0); + //U8GLIB_DOGM128 u8g(DOGLCD_SCK, DOGLCD_MOSI, DOGLCD_CS, DOGLCD_A0); // 8 stripes + U8GLIB_DOGM128_2X u8g(DOGLCD_SCK, DOGLCD_MOSI, DOGLCD_CS, DOGLCD_A0); // 4 stripes #else - U8GLIB_DOGM128 u8g(DOGLCD_CS, DOGLCD_A0); + //U8GLIB_DOGM128 u8g(DOGLCD_CS, DOGLCD_A0); // 8 stripes + U8GLIB_DOGM128_2X u8g(DOGLCD_CS, DOGLCD_A0); // 4 stripes #endif #elif ENABLED(U8GLIB_LM6059_AF) // Based on the Adafruit ST7565 (http://www.adafruit.com/products/250) - U8GLIB_LM6059 u8g(DOGLCD_CS, DOGLCD_A0); + //U8GLIB_LM6059 u8g(DOGLCD_CS, DOGLCD_A0); // 8 stripes + U8GLIB_LM6059_2X u8g(DOGLCD_CS, DOGLCD_A0); // 4 stripes #elif ENABLED(MAKRPANEL) || ENABLED(VIKI2) || ENABLED(miniVIKI) // The MaKrPanel, Mini Viki, and Viki 2.0, ST7565 controller as well - U8GLIB_NHD_C12864 u8g(DOGLCD_CS, DOGLCD_A0); + //U8GLIB_NHD_C12864 u8g(DOGLCD_CS, DOGLCD_A0); // 8 stripes + U8GLIB_NHD_C12864_2X u8g(DOGLCD_CS, DOGLCD_A0); // 4 stripes #elif ENABLED(U8GLIB_SSD1306) // Generic support for SSD1306 OLED I2C LCDs - U8GLIB_SSD1306_128X64 u8g(U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST); + //U8GLIB_SSD1306_128X64 u8g(U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST); // 8 stripes + U8GLIB_SSD1306_128X64_2X u8g(U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST); // 4 stripes #elif ENABLED(U8GLIB_SH1106) // Generic support for SH1106 OLED I2C LCDs - U8GLIB_SH1106_128X64 u8g(U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST); + //U8GLIB_SH1106_128X64 u8g(U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST); // 8 stripes + U8GLIB_SH1106_128X64_2X u8g(U8G_I2C_OPT_NONE | U8G_I2C_OPT_FAST); // 4 stripes #elif ENABLED(MINIPANEL) // The MINIPanel display - U8GLIB_MINI12864 u8g(DOGLCD_CS, DOGLCD_A0); + //U8GLIB_MINI12864 u8g(DOGLCD_CS, DOGLCD_A0); // 8 stripes + U8GLIB_MINI12864_2X u8g(DOGLCD_CS, DOGLCD_A0); // 4 stripes #else // for regular DOGM128 display with HW-SPI - U8GLIB_DOGM128 u8g(DOGLCD_CS, DOGLCD_A0); // HW-SPI Com: CS, A0 + //U8GLIB_DOGM128 u8g(DOGLCD_CS, DOGLCD_A0); // HW-SPI Com: CS, A0 // 8 stripes + U8GLIB_DOGM128_2X u8g(DOGLCD_CS, DOGLCD_A0); // HW-SPI Com: CS, A0 // 4 stripes #endif #ifndef LCD_PIXEL_WIDTH @@ -178,8 +195,15 @@ int lcd_contrast; static char currentfont = 0; -static void lcd_setFont(char font_nr) { - switch(font_nr) { +// The current graphical page being rendered +u8g_page_t &page = ((u8g_pb_t *)((u8g.getU8g())->dev->dev_mem))->p; + +// For selective rendering within a Y range +#define PAGE_UNDER(yb) (u8g.getU8g()->current_page.y0 <= (yb)) +#define PAGE_CONTAINS(ya, yb) (PAGE_UNDER(yb) && u8g.getU8g()->current_page.y1 >= (ya)) + +static void lcd_setFont(const char font_nr) { + switch (font_nr) { case FONT_STATUSMENU : {u8g.setFont(FONT_STATUSMENU_NAME); currentfont = FONT_STATUSMENU;}; break; case FONT_MENU : {u8g.setFont(FONT_MENU_NAME); currentfont = FONT_MENU;}; break; case FONT_SPECIAL : {u8g.setFont(FONT_SPECIAL_NAME); currentfont = FONT_SPECIAL;}; break; @@ -188,48 +212,43 @@ static void lcd_setFont(char font_nr) { } } -char lcd_print(char c) { +void lcd_print(const char c) { + if ((c > 0) && (c <= LCD_STR_SPECIAL_MAX)) { + u8g.setFont(FONT_SPECIAL_NAME); + u8g.print(c); + lcd_setFont(currentfont); + } + else charset_mapper(c); +} + +char lcd_print_and_count(const char c) { if ((c > 0) && (c <= LCD_STR_SPECIAL_MAX)) { u8g.setFont(FONT_SPECIAL_NAME); u8g.print(c); lcd_setFont(currentfont); return 1; - } else { - return charset_mapper(c); } + else return charset_mapper(c); } -char lcd_print(const char* str) { - char c; - int i = 0; - char n = 0; - while ((c = str[i++])) { - n += lcd_print(c); - } - return n; +void lcd_print(const char* const str) { + for (uint8_t i = 0; char c = str[i]; ++i) lcd_print(c); } /* Arduino < 1.0.0 is missing a function to print PROGMEM strings, so we need to implement our own */ -char lcd_printPGM(const char* str) { - char c; - char n = 0; - while ((c = pgm_read_byte(str++))) { - n += lcd_print(c); - } - return n; +void lcd_printPGM(const char* str) { + for (; char c = pgm_read_byte(str); ++str) lcd_print(c); } -/* Warning: This function is called from interrupt context */ +// Initialize or re-initializw the LCD static void lcd_implementation_init() { - #if defined(LCD_PIN_BL) && LCD_PIN_BL > -1 // Enable LCD backlight - pinMode(LCD_PIN_BL, OUTPUT); - digitalWrite(LCD_PIN_BL, HIGH); + #if PIN_EXISTS(LCD_BACKLIGHT) // Enable LCD backlight + OUT_WRITE(LCD_BACKLIGHT_PIN, HIGH); #endif - #if defined(LCD_PIN_RESET) && LCD_PIN_RESET > -1 - pinMode(LCD_PIN_RESET, OUTPUT); - digitalWrite(LCD_PIN_RESET, HIGH); + #if PIN_EXISTS(LCD_RESET) + OUT_WRITE(LCD_RESET_PIN, HIGH); #endif #if DISABLED(MINIPANEL) // setContrast not working for Mini Panel @@ -260,15 +279,15 @@ static void lcd_implementation_init() { } #endif // SHOW_CUSTOM_BOOTSCREEN - int offx = (u8g.getWidth() - (START_BMPWIDTH)) / 2; + const uint8_t offx = (u8g.getWidth() - (START_BMPWIDTH)) / 2; #if ENABLED(START_BMPHIGH) - int offy = 0; + constexpr uint8_t offy = 0; #else - int offy = DOG_CHAR_HEIGHT; + constexpr uint8_t offy = DOG_CHAR_HEIGHT; #endif - int txt1X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE1) - 1) * (DOG_CHAR_WIDTH)) / 2; + const uint8_t txt1X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE1) - 1) * (DOG_CHAR_WIDTH)) / 2; if (show_bootscreen) { u8g.firstPage(); @@ -278,7 +297,7 @@ static void lcd_implementation_init() { #ifndef STRING_SPLASH_LINE2 u8g.drawStr(txt1X, u8g.getHeight() - (DOG_CHAR_HEIGHT), STRING_SPLASH_LINE1); #else - int txt2X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE2) - 1) * (DOG_CHAR_WIDTH)) / 2; + const uint8_t txt2X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE2) - 1) * (DOG_CHAR_WIDTH)) / 2; u8g.drawStr(txt1X, u8g.getHeight() - (DOG_CHAR_HEIGHT) * 3 / 2, STRING_SPLASH_LINE1); u8g.drawStr(txt2X, u8g.getHeight() - (DOG_CHAR_HEIGHT) * 1 / 2, STRING_SPLASH_LINE2); #endif @@ -290,6 +309,7 @@ static void lcd_implementation_init() { #endif // SHOW_BOOTSCREEN } +// The kill screen is displayed for unrecoverable conditions void lcd_kill_screen() { lcd_setFont(FONT_MENU); u8g.setPrintPos(0, u8g.getHeight()/4*1); @@ -302,46 +322,54 @@ void lcd_kill_screen() { static void lcd_implementation_clear() { } // Automatically cleared by Picture Loop -FORCE_INLINE void _draw_centered_temp(int temp, int x, int y) { - int degsize = 6 * (temp >= 100 ? 3 : temp >= 10 ? 2 : 1); // number's pixel width +// +// Status Screen +// + +FORCE_INLINE void _draw_centered_temp(const int temp, const uint8_t x, const uint8_t y) { + const uint8_t degsize = 6 * (temp >= 100 ? 3 : temp >= 10 ? 2 : 1); // number's pixel width u8g.setPrintPos(x - (18 - degsize) / 2, y); // move left if shorter lcd_print(itostr3(temp)); lcd_printPGM(PSTR(LCD_STR_DEGREE " ")); } -FORCE_INLINE void _draw_heater_status(int x, int heater) { +FORCE_INLINE void _draw_heater_status(const uint8_t x, const int8_t heater) { #if HAS_TEMP_BED bool isBed = heater < 0; #else const bool isBed = false; #endif - _draw_centered_temp((isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater)) + 0.5, x, 7); + if (PAGE_UNDER(7)) + _draw_centered_temp((isBed ? thermalManager.degTargetBed() : thermalManager.degTargetHotend(heater)) + 0.5, x, 7); - _draw_centered_temp((isBed ? thermalManager.degBed() : thermalManager.degHotend(heater)) + 0.5, x, 28); + if (PAGE_CONTAINS(21, 28)) + _draw_centered_temp((isBed ? thermalManager.degBed() : thermalManager.degHotend(heater)) + 0.5, x, 28); - int h = isBed ? 7 : 8, - y = isBed ? 18 : 17; - if (isBed ? thermalManager.isHeatingBed() : thermalManager.isHeatingHotend(heater)) { - u8g.setColorIndex(0); // white on black - u8g.drawBox(x + h, y, 2, 2); - u8g.setColorIndex(1); // black on white - } - else { - u8g.drawBox(x + h, y, 2, 2); + if (PAGE_CONTAINS(17, 20)) { + const uint8_t h = isBed ? 7 : 8, + y = isBed ? 18 : 17; + if (isBed ? thermalManager.isHeatingBed() : thermalManager.isHeatingHotend(heater)) { + u8g.setColorIndex(0); // white on black + u8g.drawBox(x + h, y, 2, 2); + u8g.setColorIndex(1); // black on white + } + else { + u8g.drawBox(x + h, y, 2, 2); + } } } -FORCE_INLINE void _draw_axis_label(AxisEnum axis, const char *pstr, bool blink) { +FORCE_INLINE void _draw_axis_label(const AxisEnum axis, const char* const pstr, const bool blink) { if (blink) lcd_printPGM(pstr); else { if (!axis_homed[axis]) - lcd_printPGM(PSTR("?")); + u8g.print('?'); else { #if DISABLED(DISABLE_REDUCED_ACCURACY_WARNING) if (!axis_known_position[axis]) - lcd_printPGM(PSTR(" ")); + u8g.print(' '); else #endif lcd_printPGM(pstr); @@ -349,286 +377,457 @@ FORCE_INLINE void _draw_axis_label(AxisEnum axis, const char *pstr, bool blink) } } +//#define DOGM_SD_PERCENT + static void lcd_implementation_status_screen() { - u8g.setColorIndex(1); // black on white bool blink = lcd_blink(); - // Symbols menu graphics, animated fan - u8g.drawBitmapP(9, 1, STATUS_SCREENBYTEWIDTH, STATUS_SCREENHEIGHT, - #if HAS_FAN0 - blink && fanSpeeds[0] ? status_screen0_bmp : status_screen1_bmp - #else - status_screen0_bmp - #endif - ); + // Black color, white background + u8g.setColorIndex(1); - // Status Menu Font for SD info, Heater status, Fan, XYZ + // Status Menu Font lcd_setFont(FONT_STATUSMENU); + // + // Fan Animation + // + + if (PAGE_UNDER(STATUS_SCREENHEIGHT + 1)) { + + u8g.drawBitmapP(9, 1, STATUS_SCREENBYTEWIDTH, STATUS_SCREENHEIGHT, + #if HAS_FAN0 + blink && fanSpeeds[0] ? status_screen0_bmp : status_screen1_bmp + #else + status_screen0_bmp + #endif + ); + + } + + // + // Temperature Graphics and Info + // + + if (PAGE_UNDER(28)) { + // Extruders + HOTEND_LOOP() _draw_heater_status(5 + e * 25, e); + + // Heated bed + #if HOTENDS < 4 && HAS_TEMP_BED + _draw_heater_status(81, -1); + #endif + + if (PAGE_CONTAINS(20, 27)) { + // Fan + u8g.setPrintPos(104, 27); + #if HAS_FAN0 + int per = ((fanSpeeds[0] + 1) * 100) / 256; + if (per) { + lcd_print(itostr3(per)); + u8g.print('%'); + } + #endif + } + } + #if ENABLED(SDSUPPORT) + + // // SD Card Symbol - u8g.drawBox(42, 42 - (TALL_FONT_CORRECTION), 8, 7); - u8g.drawBox(50, 44 - (TALL_FONT_CORRECTION), 2, 5); - u8g.drawFrame(42, 49 - (TALL_FONT_CORRECTION), 10, 4); - u8g.drawPixel(50, 43 - (TALL_FONT_CORRECTION)); + // + if (PAGE_CONTAINS(42 - (TALL_FONT_CORRECTION), 51 - (TALL_FONT_CORRECTION))) { + // Upper box + u8g.drawBox(42, 42 - (TALL_FONT_CORRECTION), 8, 7); // 42-48 (or 41-47) + // Right edge + u8g.drawBox(50, 44 - (TALL_FONT_CORRECTION), 2, 5); // 44-48 (or 43-47) + // Bottom hollow box + u8g.drawFrame(42, 49 - (TALL_FONT_CORRECTION), 10, 4); // 49-52 (or 48-51) + // Corner pixel + u8g.drawPixel(50, 43 - (TALL_FONT_CORRECTION)); // 43 (or 42) + } + + // // Progress bar frame - u8g.drawFrame(54, 49, 73, 4 - (TALL_FONT_CORRECTION)); + // + + #define PROGRESS_BAR_X 54 + #define PROGRESS_BAR_WIDTH (LCD_PIXEL_WIDTH - PROGRESS_BAR_X) + + if (PAGE_CONTAINS(49, 52 - (TALL_FONT_CORRECTION))) // 49-52 (or 49-51) + u8g.drawFrame( + PROGRESS_BAR_X, 49, + PROGRESS_BAR_WIDTH, 4 - (TALL_FONT_CORRECTION) + ); - // SD Card Progress bar and clock if (IS_SD_PRINTING) { + + // // Progress bar solid part - u8g.drawBox(55, 50, (unsigned int)(71 * card.percentDone() * 0.01), 2 - (TALL_FONT_CORRECTION)); + // + + if (PAGE_CONTAINS(50, 51 - (TALL_FONT_CORRECTION))) // 50-51 (or just 50) + u8g.drawBox( + PROGRESS_BAR_X + 1, 50, + (unsigned int)((PROGRESS_BAR_WIDTH - 2) * card.percentDone() * 0.01), 2 - (TALL_FONT_CORRECTION) + ); + + // + // SD Percent Complete + // + + #if ENABLED(DOGM_SD_PERCENT) + if (PAGE_CONTAINS(41, 48)) { + // Percent complete + u8g.setPrintPos(55, 48); + u8g.print(itostr3(card.percentDone())); + u8g.print('%'); + } + #endif } - u8g.setPrintPos(80,48); + // + // Elapsed Time + // - char buffer[10]; - duration_t elapsed = print_job_timer.duration(); - elapsed.toDigital(buffer); - lcd_print(buffer); + #if DISABLED(DOGM_SD_PERCENT) + #define SD_DURATION_X (PROGRESS_BAR_X + (PROGRESS_BAR_WIDTH / 2) - len * (DOG_CHAR_WIDTH / 2)) + #else + #define SD_DURATION_X (LCD_PIXEL_WIDTH - len * DOG_CHAR_WIDTH) + #endif - #endif + if (PAGE_CONTAINS(41, 48)) { - // Extruders - HOTEND_LOOP() _draw_heater_status(5 + e * 25, e); - - // Heated bed - #if HOTENDS < 4 && HAS_TEMP_BED - _draw_heater_status(81, -1); - #endif - - // Fan - u8g.setPrintPos(104, 27); - #if HAS_FAN0 - int per = ((fanSpeeds[0] + 1) * 100) / 256; - if (per) { - lcd_print(itostr3(per)); - lcd_print('%'); + char buffer[10]; + duration_t elapsed = print_job_timer.duration(); + bool has_days = (elapsed.value > 60*60*24L); + uint8_t len = elapsed.toDigital(buffer, has_days); + u8g.setPrintPos(SD_DURATION_X, 48); + lcd_print(buffer); } + + #endif + + // + // XYZ Coordinates + // + + #if ENABLED(USE_SMALL_INFOFONT) + #define INFO_FONT_HEIGHT 7 + #else + #define INFO_FONT_HEIGHT 8 + #endif + + #define XYZ_BASELINE (30 + INFO_FONT_HEIGHT) + + #define X_LABEL_POS 3 + #define X_VALUE_POS 11 + #define XYZ_SPACING 40 + + // Enable to save many cycles by drawing a hollow frame + #define XYZ_HOLLOW_FRAME + #define MENU_HOLLOW_FRAME + + #if ENABLED(XYZ_HOLLOW_FRAME) + #define XYZ_FRAME_TOP 29 + #define XYZ_FRAME_HEIGHT INFO_FONT_HEIGHT + 3 + #else + #define XYZ_FRAME_TOP 30 + #define XYZ_FRAME_HEIGHT INFO_FONT_HEIGHT + 1 #endif - // X, Y, Z-Coordinates // Before homing the axis letters are blinking 'X' <-> '?'. // When axis is homed but axis_known_position is false the axis letters are blinking 'X' <-> ' '. // When everything is ok you see a constant 'X'. - #define XYZ_BASELINE 38 - #if ENABLED(USE_SMALL_INFOFONT) - u8g.drawBox(0, 30, LCD_PIXEL_WIDTH, 10); - #else - u8g.drawBox(0, 30, LCD_PIXEL_WIDTH, 9); - #endif - u8g.setColorIndex(0); // white on black + static char xstring[5], ystring[5], zstring[7]; - u8g.setPrintPos(2, XYZ_BASELINE); - _draw_axis_label(X_AXIS, PSTR(MSG_X), blink); - u8g.setPrintPos(10, XYZ_BASELINE); - lcd_print(ftostr4sign(current_position[X_AXIS])); + // At the first page, regenerate the XYZ strings + if (page.page == 0) { + strcpy(xstring, ftostr4sign(current_position[X_AXIS])); + strcpy(ystring, ftostr4sign(current_position[Y_AXIS])); + strcpy(zstring, ftostr52sp(current_position[Z_AXIS] + 0.00001)); + } - u8g.setPrintPos(43, XYZ_BASELINE); - _draw_axis_label(Y_AXIS, PSTR(MSG_Y), blink); - u8g.setPrintPos(51, XYZ_BASELINE); - lcd_print(ftostr4sign(current_position[Y_AXIS])); + if (PAGE_CONTAINS(XYZ_FRAME_TOP, XYZ_FRAME_TOP + XYZ_FRAME_HEIGHT - 1)) { - u8g.setPrintPos(83, XYZ_BASELINE); - _draw_axis_label(Z_AXIS, PSTR(MSG_Z), blink); - u8g.setPrintPos(91, XYZ_BASELINE); - lcd_print(ftostr52sp(current_position[Z_AXIS] + 0.00001)); + #if ENABLED(XYZ_HOLLOW_FRAME) + u8g.drawFrame(0, XYZ_FRAME_TOP, LCD_PIXEL_WIDTH, XYZ_FRAME_HEIGHT); // 8: 29-40 7: 29-39 + #else + u8g.drawBox(0, XYZ_FRAME_TOP, LCD_PIXEL_WIDTH, XYZ_FRAME_HEIGHT); // 8: 30-39 7: 30-37 + #endif - u8g.setColorIndex(1); // black on white + if (PAGE_CONTAINS(XYZ_BASELINE - (INFO_FONT_HEIGHT - 1), XYZ_BASELINE)) { + #if DISABLED(XYZ_HOLLOW_FRAME) + u8g.setColorIndex(0); // white on black + #endif + + u8g.setPrintPos(0 * XYZ_SPACING + X_LABEL_POS, XYZ_BASELINE); + _draw_axis_label(X_AXIS, PSTR(MSG_X), blink); + u8g.setPrintPos(0 * XYZ_SPACING + X_VALUE_POS, XYZ_BASELINE); + lcd_print(xstring); + + u8g.setPrintPos(1 * XYZ_SPACING + X_LABEL_POS, XYZ_BASELINE); + _draw_axis_label(Y_AXIS, PSTR(MSG_Y), blink); + u8g.setPrintPos(1 * XYZ_SPACING + X_VALUE_POS, XYZ_BASELINE); + lcd_print(ystring); + + u8g.setPrintPos(2 * XYZ_SPACING + X_LABEL_POS, XYZ_BASELINE); + _draw_axis_label(Z_AXIS, PSTR(MSG_Z), blink); + u8g.setPrintPos(2 * XYZ_SPACING + X_VALUE_POS, XYZ_BASELINE); + lcd_print(zstring); + + #if DISABLED(XYZ_HOLLOW_FRAME) + u8g.setColorIndex(1); // black on white + #endif + } + } + + // // Feedrate - lcd_setFont(FONT_MENU); - u8g.setPrintPos(3, 49); - lcd_print(LCD_STR_FEEDRATE[0]); + // - lcd_setFont(FONT_STATUSMENU); - u8g.setPrintPos(12, 49); - lcd_print(itostr3(feedrate_percentage)); - lcd_print('%'); + if (PAGE_CONTAINS(51 - INFO_FONT_HEIGHT, 49)) { + lcd_setFont(FONT_MENU); + u8g.setPrintPos(3, 50); + lcd_print(LCD_STR_FEEDRATE[0]); + lcd_setFont(FONT_STATUSMENU); + u8g.setPrintPos(12, 50); + lcd_print(itostr3(feedrate_percentage)); + u8g.print('%'); + } + + // // Status line - #if ENABLED(USE_SMALL_INFOFONT) - u8g.setPrintPos(0, 62); - #else - u8g.setPrintPos(0, 63); - #endif - #if DISABLED(FILAMENT_LCD_DISPLAY) - lcd_print(lcd_status_message); - #else - if (PENDING(millis(), previous_lcd_status_ms + 5000UL)) { //Display both Status message line and Filament display on the last line + // + + #define STATUS_BASELINE (55 + INFO_FONT_HEIGHT) + + if (PAGE_CONTAINS(STATUS_BASELINE + 1 - INFO_FONT_HEIGHT, STATUS_BASELINE)) { + u8g.setPrintPos(0, STATUS_BASELINE); + + #if DISABLED(FILAMENT_LCD_DISPLAY) lcd_print(lcd_status_message); - } - else { - lcd_printPGM(PSTR("dia:")); - lcd_print(ftostr12ns(filament_width_meas)); - lcd_printPGM(PSTR(" factor:")); - lcd_print(itostr3(100.0 * volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM])); - lcd_print('%'); - } - #endif -} - -static void lcd_implementation_mark_as_selected(uint8_t row, bool isSelected) { - if (isSelected) { - u8g.setColorIndex(1); // black on white - u8g.drawBox(0, row * (DOG_CHAR_HEIGHT) + 3 - (TALL_FONT_CORRECTION), LCD_PIXEL_WIDTH, DOG_CHAR_HEIGHT); - u8g.setColorIndex(0); // following text must be white on black - } - else { - u8g.setColorIndex(1); // unmarked text is black on white - } - u8g.setPrintPos((START_COL) * (DOG_CHAR_WIDTH), (row + 1) * (DOG_CHAR_HEIGHT)); -} - -#if ENABLED(LCD_INFO_MENU) || ENABLED(FILAMENT_CHANGE_FEATURE) - - static void lcd_implementation_drawmenu_static(uint8_t row, const char* pstr, bool center=true, bool invert=false, const char* valstr=NULL) { - - lcd_implementation_mark_as_selected(row, invert); - - char c; - int8_t n = LCD_WIDTH - (START_COL); - - if (center && !valstr) { - int8_t pad = (LCD_WIDTH - lcd_strlen_P(pstr)) / 2; - while (--pad >= 0) { lcd_print(' '); n--; } - } - while (n > 0 && (c = pgm_read_byte(pstr))) { - n -= lcd_print(c); - pstr++; - } - if (valstr) while (n > 0 && (c = *valstr)) { - n -= lcd_print(c); - valstr++; - } - while (n-- > 0) lcd_print(' '); - } - -#endif // LCD_INFO_MENU || FILAMENT_CHANGE_FEATURE - -static void lcd_implementation_drawmenu_generic(bool isSelected, uint8_t row, const char* pstr, char pre_char, char post_char) { - UNUSED(pre_char); - - char c; - uint8_t n = LCD_WIDTH - (START_COL) - 2; - - lcd_implementation_mark_as_selected(row, isSelected); - - while (c = pgm_read_byte(pstr)) { - n -= lcd_print(c); - pstr++; - } - while (n--) lcd_print(' '); - u8g.setPrintPos(LCD_PIXEL_WIDTH - (DOG_CHAR_WIDTH), (row + 1) * (DOG_CHAR_HEIGHT)); - lcd_print(post_char); - lcd_print(' '); -} - -static void _drawmenu_setting_edit_generic(bool isSelected, uint8_t row, const char* pstr, const char* data, bool pgm) { - char c; - uint8_t vallen = (pgm ? lcd_strlen_P(data) : (lcd_strlen((char*)data))); - uint8_t n = LCD_WIDTH - (START_COL) - 2 - vallen; - - lcd_implementation_mark_as_selected(row, isSelected); - - while (c = pgm_read_byte(pstr)) { - n -= lcd_print(c); - pstr++; - } - lcd_print(':'); - while (n--) lcd_print(' '); - u8g.setPrintPos(LCD_PIXEL_WIDTH - (DOG_CHAR_WIDTH) * vallen, (row + 1) * (DOG_CHAR_HEIGHT)); - if (pgm) lcd_printPGM(data); else lcd_print((char*)data); -} - -#define lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, data) _drawmenu_setting_edit_generic(sel, row, pstr, data, false) -#define lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, data) _drawmenu_setting_edit_generic(sel, row, pstr, data, true) - -#define lcd_implementation_drawmenu_setting_edit_int3(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, itostr3(*(data))) -#define lcd_implementation_drawmenu_setting_edit_float3(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr3(*(data))) -#define lcd_implementation_drawmenu_setting_edit_float32(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr32(*(data))) -#define lcd_implementation_drawmenu_setting_edit_float43(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr43sign(*(data))) -#define lcd_implementation_drawmenu_setting_edit_float5(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr5rj(*(data))) -#define lcd_implementation_drawmenu_setting_edit_float52(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr52sign(*(data))) -#define lcd_implementation_drawmenu_setting_edit_float51(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr51sign(*(data))) -#define lcd_implementation_drawmenu_setting_edit_long5(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr5rj(*(data))) -#define lcd_implementation_drawmenu_setting_edit_bool(sel, row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) - -//Add version for callback functions -#define lcd_implementation_drawmenu_setting_edit_callback_int3(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, itostr3(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_float3(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr3(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_float32(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr32(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_float43(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr43sign(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_float5(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr5rj(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_float52(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr52sign(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_float51(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr51sign(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_long5(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr5rj(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_bool(sel, row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) - -void lcd_implementation_drawedit(const char* pstr, const char* value=NULL) { - uint8_t rows = 1; - uint8_t lcd_width = LCD_WIDTH - (START_COL), char_width = DOG_CHAR_WIDTH; - uint8_t vallen = lcd_strlen(value); - - #if ENABLED(USE_BIG_EDIT_FONT) - if (lcd_strlen_P(pstr) <= LCD_WIDTH_EDIT - 1) { - lcd_setFont(FONT_MENU_EDIT); - lcd_width = LCD_WIDTH_EDIT + 1; - char_width = DOG_CHAR_WIDTH_EDIT; - if (lcd_strlen_P(pstr) >= LCD_WIDTH_EDIT - vallen) rows = 2; - } - else { - lcd_setFont(FONT_MENU); - } - #endif - - if (lcd_strlen_P(pstr) > LCD_WIDTH - 2 - vallen) rows = 2; - - const float kHalfChar = (DOG_CHAR_HEIGHT_EDIT) / 2; - float rowHeight = u8g.getHeight() / (rows + 1); // 1/(rows+1) = 1/2 or 1/3 - - u8g.setPrintPos(0, rowHeight + kHalfChar); - lcd_printPGM(pstr); - if (value != NULL) { - lcd_print(':'); - u8g.setPrintPos((lcd_width - 1 - vallen) * char_width, rows * rowHeight + kHalfChar); - lcd_print(value); + #else + if (PENDING(millis(), previous_lcd_status_ms + 5000UL)) { //Display both Status message line and Filament display on the last line + lcd_print(lcd_status_message); + } + else { + lcd_printPGM(PSTR("dia:")); + lcd_print(ftostr12ns(filament_width_meas)); + lcd_printPGM(PSTR(" factor:")); + lcd_print(itostr3(100.0 * volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM])); + u8g.print('%'); + } + #endif } } -#if ENABLED(SDSUPPORT) +#if ENABLED(ULTIPANEL) - static void _drawmenu_sd(bool isSelected, uint8_t row, const char* pstr, const char* filename, char* const longFilename, bool isDir) { - UNUSED(pstr); - char c; - uint8_t n = LCD_WIDTH - (START_COL) - 1; + uint8_t row_y1, row_y2; - if (longFilename[0]) { - filename = longFilename; - longFilename[n] = '\0'; + // Set the colors for a menu item based on whether it is selected + static void lcd_implementation_mark_as_selected(const uint8_t row, const bool isSelected) { + + row_y1 = row * (DOG_CHAR_HEIGHT + 2 * (TALL_FONT_CORRECTION)) + 1; + row_y2 = row_y1 + (DOG_CHAR_HEIGHT + 2 * (TALL_FONT_CORRECTION)) - 1; + + if (!PAGE_CONTAINS(row_y1 + 1, row_y1 + 1 + DOG_CHAR_HEIGHT + 2 * (TALL_FONT_CORRECTION))) return; + + if (isSelected) { + #if ENABLED(MENU_HOLLOW_FRAME) + u8g.drawHLine(0, row_y1 + 1, LCD_PIXEL_WIDTH); + u8g.drawHLine(0, row_y1 + 1 + DOG_CHAR_HEIGHT + 2 * (TALL_FONT_CORRECTION), LCD_PIXEL_WIDTH); + #else + u8g.setColorIndex(1); // black on white + u8g.drawBox(0, row_y1 + 2, LCD_PIXEL_WIDTH, DOG_CHAR_HEIGHT - 1 + 2 * (TALL_FONT_CORRECTION)); + u8g.setColorIndex(0); // white on black + #endif } + #if DISABLED(MENU_HOLLOW_FRAME) + else { + u8g.setColorIndex(1); // unmarked text is black on white + } + #endif + u8g.setPrintPos((START_COL) * (DOG_CHAR_WIDTH), row_y2); + } + + #if ENABLED(LCD_INFO_MENU) || ENABLED(FILAMENT_CHANGE_FEATURE) + + // Draw a static line of text in the same idiom as a menu item + static void lcd_implementation_drawmenu_static(const uint8_t row, const char* pstr, const bool center=true, const bool invert=false, const char* valstr=NULL) { + + lcd_implementation_mark_as_selected(row, invert); + + if (!PAGE_CONTAINS(row_y1, row_y2)) return; + + char c; + int8_t n = LCD_WIDTH - (START_COL); + + if (center && !valstr) { + int8_t pad = (LCD_WIDTH - lcd_strlen_P(pstr)) / 2; + while (--pad >= 0) { u8g.print(' '); n--; } + } + while (n > 0 && (c = pgm_read_byte(pstr))) { + n -= lcd_print_and_count(c); + pstr++; + } + if (valstr) while (n > 0 && (c = *valstr)) { + n -= lcd_print_and_count(c); + valstr++; + } + while (n-- > 0) u8g.print(' '); + } + + #endif // LCD_INFO_MENU || FILAMENT_CHANGE_FEATURE + + // Draw a generic menu item + static void lcd_implementation_drawmenu_generic(const bool isSelected, const uint8_t row, const char* pstr, const char pre_char, const char post_char) { + UNUSED(pre_char); lcd_implementation_mark_as_selected(row, isSelected); - if (isDir) lcd_print(LCD_STR_FOLDER[0]); - while ((c = *filename)) { - n -= lcd_print(c); - filename++; + if (!PAGE_CONTAINS(row_y1, row_y2)) return; + + uint8_t n = LCD_WIDTH - (START_COL) - 2; + while (char c = pgm_read_byte(pstr)) { + n -= lcd_print_and_count(c); + pstr++; } - while (n--) lcd_print(' '); + while (n--) u8g.print(' '); + u8g.setPrintPos(LCD_PIXEL_WIDTH - (DOG_CHAR_WIDTH), row_y2); + lcd_print(post_char); + u8g.print(' '); } - #define lcd_implementation_drawmenu_sdfile(sel, row, pstr, filename, longFilename) _drawmenu_sd(sel, row, pstr, filename, longFilename, false) - #define lcd_implementation_drawmenu_sddirectory(sel, row, pstr, filename, longFilename) _drawmenu_sd(sel, row, pstr, filename, longFilename, true) + // Macros for specific types of menu items + #define lcd_implementation_drawmenu_back(sel, row, pstr, dummy) lcd_implementation_drawmenu_generic(sel, row, pstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0]) + #define lcd_implementation_drawmenu_submenu(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', LCD_STR_ARROW_RIGHT[0]) + #define lcd_implementation_drawmenu_gcode(sel, row, pstr, gcode) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ') + #define lcd_implementation_drawmenu_function(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ') -#endif //SDSUPPORT + // Draw a menu item with an editable value + static void _drawmenu_setting_edit_generic(const bool isSelected, const uint8_t row, const char* pstr, const char* const data, const bool pgm) { -#define lcd_implementation_drawmenu_back(sel, row, pstr) lcd_implementation_drawmenu_generic(sel, row, pstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0]) -#define lcd_implementation_drawmenu_submenu(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', LCD_STR_ARROW_RIGHT[0]) -#define lcd_implementation_drawmenu_gcode(sel, row, pstr, gcode) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ') -#define lcd_implementation_drawmenu_function(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ') + lcd_implementation_mark_as_selected(row, isSelected); + + if (!PAGE_CONTAINS(row_y1, row_y2)) return; + + const uint8_t vallen = (pgm ? lcd_strlen_P(data) : (lcd_strlen((char*)data))); + uint8_t n = LCD_WIDTH - (START_COL) - 2 - vallen; + + while (char c = pgm_read_byte(pstr)) { + n -= lcd_print_and_count(c); + pstr++; + } + u8g.print(':'); + while (n--) u8g.print(' '); + u8g.setPrintPos(LCD_PIXEL_WIDTH - (DOG_CHAR_WIDTH) * vallen, row_y2); + if (pgm) lcd_printPGM(data); else lcd_print((char*)data); + } + + // Macros for edit items + #define lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, data) _drawmenu_setting_edit_generic(sel, row, pstr, data, false) + #define lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, data) _drawmenu_setting_edit_generic(sel, row, pstr, data, true) + + #define lcd_implementation_drawmenu_setting_edit_int3(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, itostr3(*(data))) + #define lcd_implementation_drawmenu_setting_edit_float3(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr3(*(data))) + #define lcd_implementation_drawmenu_setting_edit_float32(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr32(*(data))) + #define lcd_implementation_drawmenu_setting_edit_float43(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr43sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_float5(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr5rj(*(data))) + #define lcd_implementation_drawmenu_setting_edit_float52(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr52sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_float51(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr51sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_float62(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr62sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_long5(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr5rj(*(data))) + #define lcd_implementation_drawmenu_setting_edit_bool(sel, row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) + + #define lcd_implementation_drawmenu_setting_edit_callback_int3(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, itostr3(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_float3(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr3(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_float32(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr32(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_float43(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr43sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_float5(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr5rj(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_float52(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr52sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_float51(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr51sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_float62(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr62sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_long5(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, ftostr5rj(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_bool(sel, row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) + + void lcd_implementation_drawedit(const char* const pstr, const char* const value=NULL) { + const uint8_t labellen = lcd_strlen_P(pstr), + vallen = lcd_strlen(value); + + uint8_t rows = (labellen > LCD_WIDTH - 2 - vallen) ? 2 : 1; + + #if ENABLED(USE_BIG_EDIT_FONT) + uint8_t lcd_width, char_width; + if (labellen <= LCD_WIDTH_EDIT - 1) { + if (labellen >= LCD_WIDTH_EDIT - vallen) rows = 2; + lcd_width = LCD_WIDTH_EDIT + 1; + char_width = DOG_CHAR_WIDTH_EDIT; + lcd_setFont(FONT_MENU_EDIT); + } + else { + lcd_width = LCD_WIDTH - (START_COL); + char_width = DOG_CHAR_WIDTH; + lcd_setFont(FONT_MENU); + } + #else + constexpr uint8_t lcd_width = LCD_WIDTH - (START_COL), + char_width = DOG_CHAR_WIDTH; + #endif + + // Center either one or two rows + const uint8_t segmentHeight = u8g.getHeight() / (rows + 1); // 1 / (rows+1) = 1/2 or 1/3 + uint8_t baseline = segmentHeight + (DOG_CHAR_HEIGHT_EDIT + 1) / 2; + + if (PAGE_CONTAINS(baseline + 1 - (DOG_CHAR_HEIGHT_EDIT), baseline)) { + u8g.setPrintPos(0, baseline); + lcd_printPGM(pstr); + } + + if (value != NULL) { + baseline += (rows - 1) * segmentHeight; + if (PAGE_CONTAINS(baseline + 1 - (DOG_CHAR_HEIGHT_EDIT), baseline)) { + u8g.print(':'); + u8g.setPrintPos((lcd_width - 1 - vallen) * char_width, baseline); + lcd_print(value); + } + } + } + + #if ENABLED(SDSUPPORT) + + static void _drawmenu_sd(const bool isSelected, const uint8_t row, const char* const pstr, const char* filename, char* const longFilename, const bool isDir) { + UNUSED(pstr); + + lcd_implementation_mark_as_selected(row, isSelected); + + if (!PAGE_CONTAINS(row_y1, row_y2)) return; + + uint8_t n = LCD_WIDTH - (START_COL) - 1; + if (longFilename[0]) { + filename = longFilename; + longFilename[n] = '\0'; + } + + if (isDir) lcd_print(LCD_STR_FOLDER[0]); + + while (char c = *filename) { + n -= lcd_print_and_count(c); + filename++; + } + while (n--) u8g.print(' '); + } + + #define lcd_implementation_drawmenu_sdfile(sel, row, pstr, filename, longFilename) _drawmenu_sd(sel, row, pstr, filename, longFilename, false) + #define lcd_implementation_drawmenu_sddirectory(sel, row, pstr, filename, longFilename) _drawmenu_sd(sel, row, pstr, filename, longFilename, true) + + #endif // SDSUPPORT + +#endif // ULTIPANEL #endif //__ULTRALCD_IMPL_DOGM_H diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index ab120c2cae..a5efb0e09e 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -24,9 +24,11 @@ #define ULTRALCD_IMPL_HD44780_H /** -* Implementation of the LCD display routines for a Hitachi HD44780 display. These are common LCD character displays. -**/ + * Implementation of the LCD display routines for a Hitachi HD44780 display. + * These are the most common LCD character displays. + */ +#include "utility.h" #include "duration_t.h" extern volatile uint8_t buttons; //an extended version of the last checked buttons in a bit array. @@ -159,7 +161,11 @@ extern volatile uint8_t buttons; //an extended version of the last checked butt #include #include #define LCD_CLASS LiquidCrystal_SR - LCD_CLASS lcd(SR_DATA_PIN, SR_CLK_PIN); + #if defined(SR_STROBE_PIN) + LCD_CLASS lcd(SR_DATA_PIN, SR_CLK_PIN, SR_STROBE_PIN); + #else + LCD_CLASS lcd(SR_DATA_PIN, SR_CLK_PIN); + #endif #elif ENABLED(LCM1602) #include #include @@ -189,10 +195,10 @@ extern volatile uint8_t buttons; //an extended version of the last checked butt static void lcd_set_custom_characters( #if ENABLED(LCD_PROGRESS_BAR) - bool progress_bar_set = true + const bool info_screen_charset = true #endif ) { - byte bedTemp[8] = { + static byte bedTemp[8] = { B00000, B11111, B10101, @@ -202,7 +208,7 @@ static void lcd_set_custom_characters( B00000, B00000 }; //thanks Sonny Mounicou - byte degree[8] = { + static byte degree[8] = { B01100, B10010, B10010, @@ -212,7 +218,7 @@ static void lcd_set_custom_characters( B00000, B00000 }; - byte thermometer[8] = { + static byte thermometer[8] = { B00100, B01010, B01010, @@ -222,7 +228,7 @@ static void lcd_set_custom_characters( B10001, B01110 }; - byte uplevel[8] = { + static byte uplevel[8] = { B00100, B01110, B11111, @@ -232,27 +238,7 @@ static void lcd_set_custom_characters( B00000, B00000 }; //thanks joris - byte refresh[8] = { - B00000, - B00110, - B11001, - B11000, - B00011, - B10011, - B01100, - B00000, - }; //thanks joris - byte folder[8] = { - B00000, - B11100, - B11111, - B10001, - B10001, - B11111, - B00000, - B00000 - }; //thanks joris - byte feedrate[8] = { + static byte feedrate[8] = { B11100, B10000, B11000, @@ -262,7 +248,7 @@ static void lcd_set_custom_characters( B00101, B00000 }; //thanks Sonny Mounicou - byte clock[8] = { + static byte clock[8] = { B00000, B01110, B10011, @@ -273,69 +259,89 @@ static void lcd_set_custom_characters( B00000 }; //thanks Sonny Mounicou - #if ENABLED(LCD_PROGRESS_BAR) - static bool char_mode = false; - byte progress[3][8] = { { + lcd.createChar(LCD_STR_BEDTEMP[0], bedTemp); + lcd.createChar(LCD_STR_DEGREE[0], degree); + lcd.createChar(LCD_STR_THERMOMETER[0], thermometer); + lcd.createChar(LCD_STR_FEEDRATE[0], feedrate); + lcd.createChar(LCD_STR_CLOCK[0], clock); + + #if ENABLED(SDSUPPORT) + static byte refresh[8] = { B00000, - B10000, - B10000, - B10000, - B10000, - B10000, - B10000, - B00000 - }, { + B00110, + B11001, + B11000, + B00011, + B10011, + B01100, B00000, - B10100, - B10100, - B10100, - B10100, - B10100, - B10100, - B00000 - }, { + }; //thanks joris + static byte folder[8] = { + B00000, + B11100, + B11111, + B10001, + B10001, + B11111, B00000, - B10101, - B10101, - B10101, - B10101, - B10101, - B10101, B00000 - } }; - if (progress_bar_set != char_mode) { - char_mode = progress_bar_set; - lcd.createChar(LCD_STR_BEDTEMP[0], bedTemp); - lcd.createChar(LCD_STR_DEGREE[0], degree); - lcd.createChar(LCD_STR_THERMOMETER[0], thermometer); - lcd.createChar(LCD_STR_FEEDRATE[0], feedrate); - lcd.createChar(LCD_STR_CLOCK[0], clock); - if (progress_bar_set) { - // Progress bar characters for info screen - for (int i = 3; i--;) lcd.createChar(LCD_STR_PROGRESS[i], progress[i]); + }; //thanks joris + + #if ENABLED(LCD_PROGRESS_BAR) + static byte progress[3][8] = { { + B00000, + B10000, + B10000, + B10000, + B10000, + B10000, + B10000, + B00000 + }, { + B00000, + B10100, + B10100, + B10100, + B10100, + B10100, + B10100, + B00000 + }, { + B00000, + B10101, + B10101, + B10101, + B10101, + B10101, + B10101, + B00000 + } }; + static bool char_mode = false; + if (info_screen_charset != char_mode) { + char_mode = info_screen_charset; + if (info_screen_charset) { // Progress bar characters for info screen + for (int i = 3; i--;) lcd.createChar(LCD_STR_PROGRESS[i], progress[i]); + } + else { // Custom characters for submenus + lcd.createChar(LCD_STR_UPLEVEL[0], uplevel); + lcd.createChar(LCD_STR_REFRESH[0], refresh); + lcd.createChar(LCD_STR_FOLDER[0], folder); + } } - else { - // Custom characters for submenus - lcd.createChar(LCD_STR_UPLEVEL[0], uplevel); - lcd.createChar(LCD_STR_REFRESH[0], refresh); - lcd.createChar(LCD_STR_FOLDER[0], folder); - } - } + #else + lcd.createChar(LCD_STR_UPLEVEL[0], uplevel); + lcd.createChar(LCD_STR_REFRESH[0], refresh); + lcd.createChar(LCD_STR_FOLDER[0], folder); + #endif + #else - lcd.createChar(LCD_STR_BEDTEMP[0], bedTemp); - lcd.createChar(LCD_STR_DEGREE[0], degree); - lcd.createChar(LCD_STR_THERMOMETER[0], thermometer); lcd.createChar(LCD_STR_UPLEVEL[0], uplevel); - lcd.createChar(LCD_STR_REFRESH[0], refresh); - lcd.createChar(LCD_STR_FOLDER[0], folder); - lcd.createChar(LCD_STR_FEEDRATE[0], feedrate); - lcd.createChar(LCD_STR_CLOCK[0], clock); #endif } static void lcd_implementation_init( #if ENABLED(LCD_PROGRESS_BAR) - bool progress_bar_set = true + const bool info_screen_charset = true #endif ) { @@ -365,7 +371,7 @@ static void lcd_implementation_init( lcd_set_custom_characters( #if ENABLED(LCD_PROGRESS_BAR) - progress_bar_set + info_screen_charset #endif ); @@ -375,31 +381,26 @@ static void lcd_implementation_init( static void lcd_implementation_clear() { lcd.clear(); } /* Arduino < 1.0.0 is missing a function to print PROGMEM strings, so we need to implement our own */ -char lcd_printPGM(const char* str) { - char c, n = 0; - while ((c = pgm_read_byte(str++))) n += charset_mapper(c); - return n; +void lcd_printPGM(const char *str) { + for (; char c = pgm_read_byte(str); ++str) charset_mapper(c); } -char lcd_print(const char* str) { - char c, n = 0; - unsigned char i = 0; - while ((c = str[i++])) n += charset_mapper(c); - return n; +void lcd_print(const char* const str) { + for (uint8_t i = 0; char c = str[i]; ++i) charset_mapper(c); } -unsigned lcd_print(char c) { return charset_mapper(c); } +void lcd_print(char c) { charset_mapper(c); } #if ENABLED(SHOW_BOOTSCREEN) - void lcd_erase_line(int line) { + void lcd_erase_line(const int line) { lcd.setCursor(0, line); - for (int i = 0; i < LCD_WIDTH; i++) + for (uint8_t i = LCD_WIDTH + 1; --i;) lcd_print(' '); } // Scroll the PSTR 'text' in a 'len' wide field for 'time' milliseconds at position col,line - void lcd_scroll(int col, int line, const char* text, int len, int time) { + void lcd_scroll(const int col, const int line, const char* const text, const int len, const int time) { char tmp[LCD_WIDTH + 1] = {0}; int n = max(lcd_strlen_P(text) - len, 0); for (int i = 0; i <= n; i++) { @@ -410,7 +411,7 @@ unsigned lcd_print(char c) { return charset_mapper(c); } } } - static void logo_lines(const char *extra) { + static void logo_lines(const char* const extra) { int indent = (LCD_WIDTH - 8 - lcd_strlen_P(extra)) / 2; lcd.setCursor(indent, 0); lcd.print('\x00'); lcd_printPGM(PSTR( "------" )); lcd.print('\x01'); lcd.setCursor(indent, 1); lcd_printPGM(PSTR("|Marlin|")); lcd_printPGM(extra); @@ -528,10 +529,11 @@ unsigned lcd_print(char c) { return charset_mapper(c); } logo_lines(PSTR("")); safe_delay(2000); #endif + lcd_set_custom_characters( - #if ENABLED(LCD_PROGRESS_BAR) - false - #endif + #if ENABLED(LCD_PROGRESS_BAR) + false + #endif ); } @@ -550,16 +552,16 @@ void lcd_kill_screen() { lcd_printPGM(PSTR(MSG_PLEASE_RESET)); } -FORCE_INLINE void _draw_axis_label(AxisEnum axis, const char *pstr, bool blink) { +FORCE_INLINE void _draw_axis_label(const AxisEnum axis, const char* const pstr, const bool blink) { if (blink) lcd_printPGM(pstr); else { if (!axis_homed[axis]) - lcd_printPGM(PSTR("?")); + lcd.print('?'); else { #if DISABLED(DISABLE_REDUCED_ACCURACY_WARNING) if (!axis_known_position[axis]) - lcd_printPGM(PSTR(" ")); + lcd.print(' '); else #endif lcd_printPGM(pstr); @@ -693,7 +695,7 @@ static void lcd_implementation_status_screen() { _draw_axis_label(X_AXIS, PSTR(MSG_X), blink); lcd.print(ftostr4sign(current_position[X_AXIS])); - lcd_printPGM(PSTR(" ")); + lcd.print(' '); _draw_axis_label(Y_AXIS, PSTR(MSG_Y), blink); lcd.print(ftostr4sign(current_position[Y_AXIS])); @@ -719,7 +721,7 @@ static void lcd_implementation_status_screen() { lcd.print(itostr3(feedrate_percentage)); lcd.print('%'); - #if LCD_WIDTH > 19 && ENABLED(SDSUPPORT) + #if LCD_WIDTH >= 20 && ENABLED(SDSUPPORT) lcd.setCursor(7, 2); lcd_printPGM(PSTR("SD")); @@ -729,14 +731,14 @@ static void lcd_implementation_status_screen() { lcd_printPGM(PSTR("---")); lcd.print('%'); - #endif // LCD_WIDTH > 19 && SDSUPPORT - - lcd.setCursor(LCD_WIDTH - 6, 2); - lcd.print(LCD_STR_CLOCK[0]); + #endif // LCD_WIDTH >= 20 && SDSUPPORT char buffer[10]; duration_t elapsed = print_job_timer.duration(); - elapsed.toDigital(buffer); + uint8_t len = elapsed.toDigital(buffer); + + lcd.setCursor(LCD_WIDTH - len - 1, 2); + lcd.print(LCD_STR_CLOCK[0]); lcd_print(buffer); #endif // LCD_HEIGHT > 3 @@ -788,135 +790,160 @@ static void lcd_implementation_status_screen() { lcd_print(lcd_status_message); } -#if ENABLED(LCD_INFO_MENU) || ENABLED(FILAMENT_CHANGE_FEATURE) +#if ENABLED(ULTIPANEL) - static void lcd_implementation_drawmenu_static(uint8_t row, const char* pstr, bool center=true, bool invert=false, const char *valstr=NULL) { - UNUSED(invert); - char c; - int8_t n = LCD_WIDTH; - lcd.setCursor(0, row); - if (center && !valstr) { - int8_t pad = (LCD_WIDTH - lcd_strlen_P(pstr)) / 2; - while (--pad >= 0) { lcd.print(' '); n--; } + #if ENABLED(LCD_INFO_MENU) || ENABLED(FILAMENT_CHANGE_FEATURE) + + static void lcd_implementation_drawmenu_static(const uint8_t row, const char* pstr, const bool center=true, const bool invert=false, const char *valstr=NULL) { + UNUSED(invert); + char c; + int8_t n = LCD_WIDTH; + lcd.setCursor(0, row); + if (center && !valstr) { + int8_t pad = (LCD_WIDTH - lcd_strlen_P(pstr)) / 2; + while (--pad >= 0) { lcd.print(' '); n--; } + } + while (n > 0 && (c = pgm_read_byte(pstr))) { + n -= charset_mapper(c); + pstr++; + } + if (valstr) while (n > 0 && (c = *valstr)) { + n -= charset_mapper(c); + valstr++; + } + while (n-- > 0) lcd.print(' '); } - while (n > 0 && (c = pgm_read_byte(pstr))) { - n -= lcd_print(c); + + #endif // LCD_INFO_MENU || FILAMENT_CHANGE_FEATURE + + static void lcd_implementation_drawmenu_generic(const bool sel, const uint8_t row, const char* pstr, const char pre_char, const char post_char) { + char c; + uint8_t n = LCD_WIDTH - 2; + lcd.setCursor(0, row); + lcd.print(sel ? pre_char : ' '); + while ((c = pgm_read_byte(pstr)) && n > 0) { + n -= charset_mapper(c); pstr++; } - if (valstr) while (n > 0 && (c = *valstr)) { - n -= lcd_print(c); - valstr++; - } - while (n-- > 0) lcd.print(' '); - } - -#endif // LCD_INFO_MENU || FILAMENT_CHANGE_FEATURE - -static void lcd_implementation_drawmenu_generic(bool sel, uint8_t row, const char* pstr, char pre_char, char post_char) { - char c; - uint8_t n = LCD_WIDTH - 2; - lcd.setCursor(0, row); - lcd.print(sel ? pre_char : ' '); - while ((c = pgm_read_byte(pstr)) && n > 0) { - n -= lcd_print(c); - pstr++; - } - while (n--) lcd.print(' '); - lcd.print(post_char); -} - -static void lcd_implementation_drawmenu_setting_edit_generic(bool sel, uint8_t row, const char* pstr, char pre_char, char* data) { - char c; - uint8_t n = LCD_WIDTH - 2 - lcd_strlen(data); - lcd.setCursor(0, row); - lcd.print(sel ? pre_char : ' '); - while ((c = pgm_read_byte(pstr)) && n > 0) { - n -= lcd_print(c); - pstr++; - } - lcd.print(':'); - while (n--) lcd.print(' '); - lcd_print(data); -} -static void lcd_implementation_drawmenu_setting_edit_generic_P(bool sel, uint8_t row, const char* pstr, char pre_char, const char* data) { - char c; - uint8_t n = LCD_WIDTH - 2 - lcd_strlen_P(data); - lcd.setCursor(0, row); - lcd.print(sel ? pre_char : ' '); - while ((c = pgm_read_byte(pstr)) && n > 0) { - n -= lcd_print(c); - pstr++; - } - lcd.print(':'); - while (n--) lcd.print(' '); - lcd_printPGM(data); -} - -#define lcd_implementation_drawmenu_setting_edit_int3(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', itostr3(*(data))) -#define lcd_implementation_drawmenu_setting_edit_float3(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr3(*(data))) -#define lcd_implementation_drawmenu_setting_edit_float32(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr32(*(data))) -#define lcd_implementation_drawmenu_setting_edit_float43(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr43sign(*(data))) -#define lcd_implementation_drawmenu_setting_edit_float5(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr5rj(*(data))) -#define lcd_implementation_drawmenu_setting_edit_float52(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr52sign(*(data))) -#define lcd_implementation_drawmenu_setting_edit_float51(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr51sign(*(data))) -#define lcd_implementation_drawmenu_setting_edit_long5(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr5rj(*(data))) -#define lcd_implementation_drawmenu_setting_edit_bool(sel, row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) - -//Add version for callback functions -#define lcd_implementation_drawmenu_setting_edit_callback_int3(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', itostr3(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_float3(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr3(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_float32(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr32(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_float43(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr43sign(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_float5(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr5rj(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_float52(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr52sign(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_float51(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr51sign(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_long5(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr5rj(*(data))) -#define lcd_implementation_drawmenu_setting_edit_callback_bool(sel, row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) - -void lcd_implementation_drawedit(const char* pstr, const char* value=NULL) { - lcd.setCursor(1, 1); - lcd_printPGM(pstr); - if (value != NULL) { - lcd.print(':'); - lcd.setCursor(LCD_WIDTH - lcd_strlen(value), 1); - lcd_print(value); - } -} - -#if ENABLED(SDSUPPORT) - - static void lcd_implementation_drawmenu_sd(bool sel, uint8_t row, const char* pstr, const char* filename, char* longFilename, uint8_t concat, char post_char) { - UNUSED(pstr); - char c; - uint8_t n = LCD_WIDTH - concat; - lcd.setCursor(0, row); - lcd.print(sel ? '>' : ' '); - if (longFilename[0]) { - filename = longFilename; - longFilename[n] = '\0'; - } - while ((c = *filename) && n > 0) { - n -= lcd_print(c); - filename++; - } while (n--) lcd.print(' '); lcd.print(post_char); } - static void lcd_implementation_drawmenu_sdfile(bool sel, uint8_t row, const char* pstr, const char* filename, char* longFilename) { - lcd_implementation_drawmenu_sd(sel, row, pstr, filename, longFilename, 2, ' '); + static void lcd_implementation_drawmenu_setting_edit_generic(const bool sel, const uint8_t row, const char* pstr, const char pre_char, const char* const data) { + char c; + uint8_t n = LCD_WIDTH - 2 - lcd_strlen(data); + lcd.setCursor(0, row); + lcd.print(sel ? pre_char : ' '); + while ((c = pgm_read_byte(pstr)) && n > 0) { + n -= charset_mapper(c); + pstr++; + } + lcd.print(':'); + while (n--) lcd.print(' '); + lcd_print(data); + } + static void lcd_implementation_drawmenu_setting_edit_generic_P(const bool sel, const uint8_t row, const char* pstr, const char pre_char, const char* const data) { + char c; + uint8_t n = LCD_WIDTH - 2 - lcd_strlen_P(data); + lcd.setCursor(0, row); + lcd.print(sel ? pre_char : ' '); + while ((c = pgm_read_byte(pstr)) && n > 0) { + n -= charset_mapper(c); + pstr++; + } + lcd.print(':'); + while (n--) lcd.print(' '); + lcd_printPGM(data); } - static void lcd_implementation_drawmenu_sddirectory(bool sel, uint8_t row, const char* pstr, const char* filename, char* longFilename) { - lcd_implementation_drawmenu_sd(sel, row, pstr, filename, longFilename, 2, LCD_STR_FOLDER[0]); + #define lcd_implementation_drawmenu_setting_edit_int3(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', itostr3(*(data))) + #define lcd_implementation_drawmenu_setting_edit_float3(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr3(*(data))) + #define lcd_implementation_drawmenu_setting_edit_float32(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr32(*(data))) + #define lcd_implementation_drawmenu_setting_edit_float43(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr43sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_float5(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr5rj(*(data))) + #define lcd_implementation_drawmenu_setting_edit_float52(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr52sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_float51(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr51sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_float62(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr62sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_long5(sel, row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr5rj(*(data))) + #define lcd_implementation_drawmenu_setting_edit_bool(sel, row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) + + //Add version for callback functions + #define lcd_implementation_drawmenu_setting_edit_callback_int3(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', itostr3(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_float3(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr3(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_float32(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr32(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_float43(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr43sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_float5(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr5rj(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_float52(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr52sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_float51(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr51sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_float62(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr62sign(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_long5(sel, row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, '>', ftostr5rj(*(data))) + #define lcd_implementation_drawmenu_setting_edit_callback_bool(sel, row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) + + void lcd_implementation_drawedit(const char* pstr, const char* const value=NULL) { + lcd.setCursor(1, 1); + lcd_printPGM(pstr); + if (value != NULL) { + lcd.print(':'); + lcd.setCursor(LCD_WIDTH - lcd_strlen(value), 1); + lcd_print(value); + } } -#endif //SDSUPPORT + #if ENABLED(SDSUPPORT) -#define lcd_implementation_drawmenu_back(sel, row, pstr) lcd_implementation_drawmenu_generic(sel, row, pstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0]) -#define lcd_implementation_drawmenu_submenu(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', LCD_STR_ARROW_RIGHT[0]) -#define lcd_implementation_drawmenu_gcode(sel, row, pstr, gcode) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ') -#define lcd_implementation_drawmenu_function(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ') + static void lcd_implementation_drawmenu_sd(const bool sel, const uint8_t row, const char* const pstr, const char* filename, char* const longFilename, const uint8_t concat, const char post_char) { + UNUSED(pstr); + char c; + uint8_t n = LCD_WIDTH - concat; + lcd.setCursor(0, row); + lcd.print(sel ? '>' : ' '); + if (longFilename[0]) { + filename = longFilename; + longFilename[n] = '\0'; + } + while ((c = *filename) && n > 0) { + n -= charset_mapper(c); + filename++; + } + while (n--) lcd.print(' '); + lcd.print(post_char); + } + + static void lcd_implementation_drawmenu_sdfile(const bool sel, const uint8_t row, const char* pstr, const char* filename, char* const longFilename) { + lcd_implementation_drawmenu_sd(sel, row, pstr, filename, longFilename, 2, ' '); + } + + static void lcd_implementation_drawmenu_sddirectory(const bool sel, const uint8_t row, const char* pstr, const char* filename, char* const longFilename) { + lcd_implementation_drawmenu_sd(sel, row, pstr, filename, longFilename, 2, LCD_STR_FOLDER[0]); + } + + #endif // SDSUPPORT + + #define lcd_implementation_drawmenu_back(sel, row, pstr, dummy) lcd_implementation_drawmenu_generic(sel, row, pstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0]) + #define lcd_implementation_drawmenu_submenu(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', LCD_STR_ARROW_RIGHT[0]) + #define lcd_implementation_drawmenu_gcode(sel, row, pstr, gcode) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ') + #define lcd_implementation_drawmenu_function(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ') + + #if ENABLED(LCD_HAS_SLOW_BUTTONS) + + extern millis_t next_button_update_ms; + + static uint8_t lcd_implementation_read_slow_buttons() { + #if ENABLED(LCD_I2C_TYPE_MCP23017) + // Reading these buttons this is likely to be too slow to call inside interrupt context + // so they are called during normal lcd_update + uint8_t slow_bits = lcd.readButtons() << B_I2C_BTN_OFFSET; + #if ENABLED(LCD_I2C_VIKI) + if ((slow_bits & (B_MI | B_RI)) && PENDING(millis(), next_button_update_ms)) // LCD clicked + slow_bits &= ~(B_MI | B_RI); // Disable LCD clicked buttons if screen is updated + #endif // LCD_I2C_VIKI + return slow_bits; + #endif // LCD_I2C_TYPE_MCP23017 + } + + #endif // LCD_HAS_SLOW_BUTTONS + +#endif // ULTIPANEL #if ENABLED(LCD_HAS_STATUS_INDICATORS) @@ -956,23 +983,4 @@ void lcd_implementation_drawedit(const char* pstr, const char* value=NULL) { #endif // LCD_HAS_STATUS_INDICATORS -#if ENABLED(LCD_HAS_SLOW_BUTTONS) - - extern millis_t next_button_update_ms; - - static uint8_t lcd_implementation_read_slow_buttons() { - #if ENABLED(LCD_I2C_TYPE_MCP23017) - // Reading these buttons this is likely to be too slow to call inside interrupt context - // so they are called during normal lcd_update - uint8_t slow_bits = lcd.readButtons() << B_I2C_BTN_OFFSET; - #if ENABLED(LCD_I2C_VIKI) - if ((slow_bits & (B_MI | B_RI)) && PENDING(millis(), next_button_update_ms)) // LCD clicked - slow_bits &= ~(B_MI | B_RI); // Disable LCD clicked buttons if screen is updated - #endif // LCD_I2C_VIKI - return slow_bits; - #endif // LCD_I2C_TYPE_MCP23017 - } - -#endif // LCD_HAS_SLOW_BUTTONS - #endif // ULTRALCD_IMPL_HD44780_H diff --git a/Marlin/ultralcd_st7920_u8glib_rrd.h b/Marlin/ultralcd_st7920_u8glib_rrd.h index 7226f55c9e..1dc39360f9 100644 --- a/Marlin/ultralcd_st7920_u8glib_rrd.h +++ b/Marlin/ultralcd_st7920_u8glib_rrd.h @@ -106,12 +106,18 @@ static void ST7920_SWSPI_SND_8BIT(uint8_t val) { ST7920_SND_BIT; // 8 } -#define ST7920_CS() {WRITE(ST7920_CS_PIN,1);u8g_10MicroDelay();} -#define ST7920_NCS() {WRITE(ST7920_CS_PIN,0);} -#define ST7920_SET_CMD() {ST7920_SWSPI_SND_8BIT(0xf8);u8g_10MicroDelay();} -#define ST7920_SET_DAT() {ST7920_SWSPI_SND_8BIT(0xfa);u8g_10MicroDelay();} -#define ST7920_WRITE_BYTE(a) {ST7920_SWSPI_SND_8BIT((uint8_t)((a)&0xf0u));ST7920_SWSPI_SND_8BIT((uint8_t)((a)<<4u));u8g_10MicroDelay();} -#define ST7920_WRITE_BYTES(p,l) {uint8_t i;for(i=0;i 0 + #define U8G_DELAY() delayMicroseconds(DOGM_SPI_DELAY_US) +#else + #define U8G_DELAY() u8g_10MicroDelay() +#endif + +#define ST7920_CS() { WRITE(ST7920_CS_PIN,1); U8G_DELAY(); } +#define ST7920_NCS() { WRITE(ST7920_CS_PIN,0); } +#define ST7920_SET_CMD() { ST7920_SWSPI_SND_8BIT(0xf8); U8G_DELAY(); } +#define ST7920_SET_DAT() { ST7920_SWSPI_SND_8BIT(0xfa); U8G_DELAY(); } +#define ST7920_WRITE_BYTE(a) { ST7920_SWSPI_SND_8BIT((uint8_t)((a)&0xf0u)); ST7920_SWSPI_SND_8BIT((uint8_t)((a)<<4u)); U8G_DELAY(); } +#define ST7920_WRITE_BYTES(p,l) { for (uint8_t i = l + 1; --i;) { ST7920_SWSPI_SND_8BIT(*p&0xf0); ST7920_SWSPI_SND_8BIT(*p<<4); p++; } U8G_DELAY(); } uint8_t u8g_dev_rrd_st7920_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg) { uint8_t i, y; @@ -167,13 +173,13 @@ uint8_t u8g_dev_rrd_st7920_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, vo } break; } -#if PAGE_HEIGHT == 8 - return u8g_dev_pb8h1_base_fn(u8g, dev, msg, arg); -#elif PAGE_HEIGHT == 16 - return u8g_dev_pb16h1_base_fn(u8g, dev, msg, arg); -#else - return u8g_dev_pb32h1_base_fn(u8g, dev, msg, arg); -#endif + #if PAGE_HEIGHT == 8 + return u8g_dev_pb8h1_base_fn(u8g, dev, msg, arg); + #elif PAGE_HEIGHT == 16 + return u8g_dev_pb16h1_base_fn(u8g, dev, msg, arg); + #else + return u8g_dev_pb32h1_base_fn(u8g, dev, msg, arg); + #endif } uint8_t u8g_dev_st7920_128x64_rrd_buf[(LCD_PIXEL_WIDTH) * (PAGE_HEIGHT) / 8] U8G_NOCOMMON; diff --git a/Marlin/utf_mapper.h b/Marlin/utf_mapper.h index bba85e180d..6bb2d732d1 100644 --- a/Marlin/utf_mapper.h +++ b/Marlin/utf_mapper.h @@ -40,40 +40,42 @@ #define MAPPER_ONE_TO_ONE #elif ENABLED(DISPLAY_CHARSET_ISO10646_GREEK) #define MAPPER_ONE_TO_ONE + #elif ENABLED(DISPLAY_CHARSET_ISO10646_TR) + #define MAPPER_ONE_TO_ONE #endif #else // SIMULATE_ROMFONT #if DISPLAY_CHARSET_HD44780 == JAPANESE #if ENABLED(MAPPER_C2C3) const PROGMEM uint8_t utf_recode[] = { // 0 1 2 3 4 5 6 7 8 9 a b c d e f This is fair for symbols - 0x20,0x3f,0xec,0xed,0x3f,0x5c,0x7c,0x3f,0x22,0x63,0x61,0x7f,0x3f,0x3f,0x52,0xb0, // c2a - // ' ' ¢ £ ­ l " c a « R - 0xdf,0x3f,0x32,0x33,0x27,0xe4,0xf1,0xa5,0x2c,0x31,0xdf,0x7e,0x3f,0x3f,0x3f,0x3f, // c2b but relatively bad for letters. - // ° 2 3 ` N p . , 1 ° » - 0x3f,0x3f,0x3f,0x3f,0xe1,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f, // c38 - // ä - 0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0xef,0x78,0x3f,0x3f,0x3f,0x3f,0xf5,0x3f,0x3f,0xe2, // c39 missing characters display as '?' - // ö x ü ß - 0x3f,0x3f,0x3f,0x3f,0xe1,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f, // c3a - // ä - 0x3f,0xee,0x3f,0x3f,0x3f,0x3f,0xef,0xfd,0x3f,0x3f,0x3f,0x3f,0xf5,0x3f,0x3f,0x3f // c3b - // n ö ÷ ü + 0x20,0x3f,0xec,0xed,0x3f,0x5c,0x7c,0x3f,0x22,0x63,0x61,0x7f,0x3f,0x3f,0x52,0xb0, // c2a + //' ' ¢ £ ­ l " c a « R + 0xdf,0x3f,0x32,0x33,0x27,0xe4,0xf1,0xa5,0x2c,0x31,0xdf,0x7e,0x3f,0x3f,0x3f,0x3f, // c2b but relatively bad for letters. + // ° 2 3 ` N p . , 1 ° » + 0x3f,0x3f,0x3f,0x3f,0xe1,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f, // c38 + // ä + 0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0xef,0x78,0x3f,0x3f,0x3f,0x3f,0xf5,0x3f,0x3f,0xe2, // c39 missing characters display as '?' + // ö x ü ß + 0x3f,0x3f,0x3f,0x3f,0xe1,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f,0x3f, // c3a + // ä + 0x3f,0xee,0x3f,0x3f,0x3f,0x3f,0xef,0xfd,0x3f,0x3f,0x3f,0x3f,0xf5,0x3f,0x3f,0x3f // c3b + // n ö ÷ ü }; #elif ENABLED(MAPPER_E382E383) const PROGMEM uint8_t utf_recode[] = { // 0 1 2 3 4 5 6 7 8 9 a b c d e f - 0x3d,0xb1,0xb1,0xa8,0xb2,0xa9,0xb3,0xaa,0xb4,0xab,0xb5,0xb6,0xb6,0xb7,0xb7,0xb8, // e382a Please test and correct - // = ア ア ィ イ ゥ ウ ェ エ ォ オ ガ ガ キ キ ク - 0xb8,0xb9,0xb9,0xba,0xba,0xbb,0xbb,0xbc,0xbc,0xbd,0xbd,0xbe,0xbe,0xbf,0xbf,0xc0, // e382b - // ク ケ ケ コ コ サ サ シ シ ス ス セ セ ソ ソ タ - 0xc0,0xc1,0xc1,0xc2,0xc2,0xc2,0xc3,0xc3,0xc4,0xc4,0xc5,0xc6,0xc7,0xc8,0xc9,0xca, // e3838 - // タ チ チ ッ ッ ッ テ テ ト ト ナ ニ ヌ ネ ノ ハ - 0xca,0xca,0xcb,0xcb,0xcb,0xcc,0xcc,0xcc,0xcd,0xcd,0xcd,0xce,0xce,0xce,0xcf,0xd0, // e3839 - // ハ ハ ヒ ヒ ヒ フ フ フ ヘ ヘ ヘ ホ ホ ホ マ ミ - 0xd1,0xd2,0xd3,0xd4,0xd4,0xd5,0xd5,0xae,0xd6,0xd7,0xd8,0xd9,0xda,0xdb,0xdc,0xdc, // e383a - // ム メ モ ャ ャ ユ ユ ョ ヨ ラ リ ル レ ロ ワ ワ - 0xec,0xa7,0xa6,0xdd,0xcc,0x3f,0x3f,0x3f,0x3f,0x3f,0xa6,0xa5,0xb0,0xa4,0xa4,0x3f // e383b - // ヰ ヱ ヲ ン フ ? ? ? ? ? ヲ ・ ー ヽ ヽ ? + 0x3d,0xb1,0xb1,0xa8,0xb2,0xa9,0xb3,0xaa,0xb4,0xab,0xb5,0xb6,0xb6,0xb7,0xb7,0xb8, // e382a Please test and correct + // = ア ア ィ イ ゥ ウ ェ エ ォ オ ガ ガ キ キ ク + 0xb8,0xb9,0xb9,0xba,0xba,0xbb,0xbb,0xbc,0xbc,0xbd,0xbd,0xbe,0xbe,0xbf,0xbf,0xc0, // e382b + // ク ケ ケ コ コ サ サ シ シ ス ス セ セ ソ ソ タ + 0xc0,0xc1,0xc1,0xc2,0xc2,0xc2,0xc3,0xc3,0xc4,0xc4,0xc5,0xc6,0xc7,0xc8,0xc9,0xca, // e3838 + // タ チ チ ッ ッ ッ テ テ ト ト ナ ニ ヌ ネ ノ ハ + 0xca,0xca,0xcb,0xcb,0xcb,0xcc,0xcc,0xcc,0xcd,0xcd,0xcd,0xce,0xce,0xce,0xcf,0xd0, // e3839 + // ハ ハ ヒ ヒ ヒ フ フ フ ヘ ヘ ヘ ホ ホ ホ マ ミ + 0xd1,0xd2,0xd3,0xd4,0xd4,0xd5,0xd5,0xae,0xd6,0xd7,0xd8,0xd9,0xda,0xdb,0xdc,0xdc, // e383a + // ム メ モ ャ ャ ユ ユ ョ ヨ ラ リ ル レ ロ ワ ワ + 0xec,0xa7,0xa6,0xdd,0xcc,0x3f,0x3f,0x3f,0x3f,0x3f,0xa6,0xa5,0xb0,0xa4,0xa4,0x3f // e383b + // ヰ ヱ ヲ ン フ ? ? ? ? ? ヲ ・ ー ヽ ヽ ? }; #elif ENABLED(MAPPER_D0D1) #error "Cyrillic on a JAPANESE display makes no sense. There are no matching symbols." @@ -83,31 +85,31 @@ #if ENABLED(MAPPER_C2C3) const PROGMEM uint8_t utf_recode[] = { // 0 1 2 3 4 5 6 7 8 9 a b c d e f This is relative complete. - 0x20,0xa1,0xa2,0xa3,0xa4,0xa5,0xa6,0xa7,0x22,0xa9,0xaa,0xab,0x3f,0x3f,0xae,0x3f, // c2a ¡¢£¤¥¦§¨©ª«¬­®¯ - // ' ' ¡ ¢ £ ¤ ¥ ¦ § " © ª « ? ? ® ? - 0xb0,0xb1,0xb2,0xb3,0x27,0xb5,0xb6,0xb7,0x2c,0xb9,0xba,0xbb,0xbc,0xbd,0xbe,0xbf, // c2b °±²³´µ¶·¸¹º»¼½¾¿ - // ° ± ³ ² ? µ ¶ · , ¹ º » ¼ ½ ¾ ¿ - 0xc0,0xc1,0xc2,0xc3,0xc4,0xc5,0xc6,0xc7,0xc8,0xc9,0xca,0xcb,0xcc,0xcd,0xce,0xcf, // c38 ÀÁÃÄÅÆÇÈÉÊËÌÍÎÏ - // À Á Â Ã Ä Å Æ Ç È É Ê Ë Ì Í Î Ï - 0xd0,0xd1,0xd2,0xd3,0xd4,0xd5,0xd6,0xd7,0xd8,0xd9,0xda,0xdb,0xdc,0xdd,0xde,0xdf, // c39 ÐÑÓÔÕÖרÙÚÛÜÝÞß - // Ð Ñ Ò Ó Ô Õ Ö × Ø Ù Ú Û Ü Ý Þ ß - 0xe0,0xe1,0xe2,0xe3,0xe4,0xe5,0xe6,0xe7,0xe8,0xe9,0xea,0xeb,0xec,0xed,0xee,0xef, // c3a àáãäåæçèéêëìíîï - // à á â ã ä å æ ç è é ê ë ì í î ï - 0xf0,0xf1,0xf2,0xf3,0xf4,0xf5,0xf6,0xf7,0xf8,0xf9,0xfa,0xfb,0xfc,0xfd,0xfe,0xff // c3b ðñóôõö÷øùúûüýþÿ - // ð ñ ò ó ô õ ö ÷ ø ù ú û ü ý þ ÿ + 0x20,0xa1,0xa2,0xa3,0xa4,0xa5,0xa6,0xa7,0x22,0xa9,0xaa,0xab,0x3f,0x3f,0xae,0x3f, // c2a ¡¢£¤¥¦§¨©ª«¬­®¯ + //' ' ¡ ¢ £ ¤ ¥ ¦ § " © ª « ? ? ® ? + 0xb0,0xb1,0xb2,0xb3,0x27,0xb5,0xb6,0xb7,0x2c,0xb9,0xba,0xbb,0xbc,0xbd,0xbe,0xbf, // c2b °±²³´µ¶·¸¹º»¼½¾¿ + // ° ± ³ ² ? µ ¶ · , ¹ º » ¼ ½ ¾ ¿ + 0xc0,0xc1,0xc2,0xc3,0xc4,0xc5,0xc6,0xc7,0xc8,0xc9,0xca,0xcb,0xcc,0xcd,0xce,0xcf, // c38 ÀÁÃÄÅÆÇÈÉÊËÌÍÎÏ + // À Á Â Ã Ä Å Æ Ç È É Ê Ë Ì Í Î Ï + 0xd0,0xd1,0xd2,0xd3,0xd4,0xd5,0xd6,0xd7,0xd8,0xd9,0xda,0xdb,0xdc,0xdd,0xde,0xdf, // c39 ÐÑÓÔÕÖרÙÚÛÜÝÞß + // Ð Ñ Ò Ó Ô Õ Ö × Ø Ù Ú Û Ü Ý Þ ß + 0xe0,0xe1,0xe2,0xe3,0xe4,0xe5,0xe6,0xe7,0xe8,0xe9,0xea,0xeb,0xec,0xed,0xee,0xef, // c3a àáãäåæçèéêëìíîï + // à á â ã ä å æ ç è é ê ë ì í î ï + 0xf0,0xf1,0xf2,0xf3,0xf4,0xf5,0xf6,0xf7,0xf8,0xf9,0xfa,0xfb,0xfc,0xfd,0xfe,0xff // c3b ðñóôõö÷øùúûüýþÿ + // ð ñ ò ó ô õ ö ÷ ø ù ú û ü ý þ ÿ }; #elif ENABLED(MAPPER_D0D1) #define MAPPER_D0D1_MOD const PROGMEM uint8_t utf_recode[] = {//0 1 2 3 4 5 6 7 8 9 a b c d e f - 0x41,0x80,0x42,0x92,0x81,0x45,0x82,0x83,0x84,0x85,0x4b,0x86,0x4d,0x48,0x4f,0x87, // d0a - // A Б B Г Д E Ж З И Й K Л M H O П - 0x50,0x43,0x54,0x88,0xd8,0x58,0x89,0x8a,0x8b,0x8c,0x8d,0x8e,0x62,0x8f,0xac,0xad, // d0b - // P C T У Ф X Ч ч Ш Щ Ъ Ы b Э Ю Я - 0x61,0x36,0x42,0x92,0x81,0x65,0x82,0xb3,0x84,0x85,0x6b,0x86,0x4d,0x48,0x6f,0x87, // d18 - // a 6 B Г Д e Ж ³ И Й k Л M H o П - 0x70,0x63,0x54,0x79,0xd8,0x78,0x89,0x8a,0x8b,0x8c,0x8d,0x8e,0x62,0x8f,0xac,0xad // d19 - // p c T y Ф x Ч ч Ш Щ Ъ Ы b Э Ю Я + 0x41,0x80,0x42,0x92,0x81,0x45,0x82,0x83,0x84,0x85,0x4b,0x86,0x4d,0x48,0x4f,0x87, // d0a + // A Б B Г Д E Ж З И Й K Л M H O П + 0x50,0x43,0x54,0x88,0xd8,0x58,0x89,0x8a,0x8b,0x8c,0x8d,0x8e,0x62,0x8f,0xac,0xad, // d0b + // P C T У Ф X Ч ч Ш Щ Ъ Ы b Э Ю Я + 0x61,0x36,0x42,0x92,0x81,0x65,0x82,0xb3,0x84,0x85,0x6b,0x86,0x4d,0x48,0x6f,0x87, // d18 + // a 6 B Г Д e Ж ³ И Й k Л M H o П + 0x70,0x63,0x54,0x79,0xd8,0x78,0x89,0x8a,0x8b,0x8c,0x8d,0x8e,0x62,0x8f,0xac,0xad // d19 + // p c T y Ф x Ч ч Ш Щ Ъ Ы b Э Ю Я }; #elif ENABLED(MAPPER_E382E383) #error "Katakana on a WESTERN display makes no sense. There are no matching symbols." @@ -119,23 +121,23 @@ // it is a Russian alphabet translation // except 0401 --> 0xa2 = Ё, 0451 --> 0xb5 = ё const PROGMEM uint8_t utf_recode[] = - { 0x41,0xa0,0x42,0xa1,0xe0,0x45,0xa3,0xa4, // unicode U+0400 to U+047f - // A Б->Ё B Г Д E Ж З // 0 Ѐ Ё Ђ Ѓ Є Ѕ І Ї - 0xa5,0xa6,0x4b,0xa7,0x4d,0x48,0x4f,0xa8, // Ј Љ Њ Ћ Ќ Ѝ Ў Џ - // И Й K Л M H O П // 1 А Б В Г Д Е Ж З - 0x50,0x43,0x54,0xa9,0xaa,0x58,0xe1,0xab, // И Й К Л М Н О П - // P C T У Ф X Ч ч // 2 Р С Т У Ф Х Г Ч - 0xac,0xe2,0xad,0xae,0x62,0xaf,0xb0,0xb1, // Ш Щ Ъ Ы Ь Э Ю Я - // Ш Щ Ъ Ы b Э Ю Я // 3 а б в г д е ж з - 0x61,0xb2,0xb3,0xb4,0xe3,0x65,0xb6,0xb7, // и й к л м н о п - // a б->ё в г д e ж з // 4 р с т у ф х ц ч - 0xb8,0xb9,0xba,0xbb,0xbc,0xbd,0x6f,0xbe, // ш щ ъ ы ь э ю я - // и й к л м н o п // 5 ѐ ё ђ ѓ є ѕ і ї - 0x70,0x63,0xbf,0x79,0xe4,0x78,0xe5,0xc0, // ј љ њ ћ ќ ѝ ў џ - // p c т y ф x ц ч // 6 Ѡ ѡ Ѣ ѣ Ѥ ѥ Ѧ ѧ - 0xc1,0xe6,0xc2,0xc3,0xc4,0xc5,0xc6,0xc7 // Ѫ ѩ Ѫ ѫ Ѭ ѭ Ѯ ѯ - // ш щ ъ ы ь э ю я // 7 Ѱ ѱ Ѳ ѳ Ѵ ѵ Ѷ ѷ - }; // ѻ ѹ Ѻ ѻ Ѽ ѽ Ѿ ѿ + { 0x41,0xa0,0x42,0xa1,0xe0,0x45,0xa3,0xa4, // unicode U+0400 to U+047f + // A Б->Ё B Г Д E Ж З // 0 Ѐ Ё Ђ Ѓ Є Ѕ І Ї + 0xa5,0xa6,0x4b,0xa7,0x4d,0x48,0x4f,0xa8, // Ј Љ Њ Ћ Ќ Ѝ Ў Џ + // И Й K Л M H O П // 1 А Б В Г Д Е Ж З + 0x50,0x43,0x54,0xa9,0xaa,0x58,0xe1,0xab, // И Й К Л М Н О П + // P C T У Ф X Ч ч // 2 Р С Т У Ф Х Г Ч + 0xac,0xe2,0xad,0xae,0x62,0xaf,0xb0,0xb1, // Ш Щ Ъ Ы Ь Э Ю Я + // Ш Щ Ъ Ы b Э Ю Я // 3 а б в г д е ж з + 0x61,0xb2,0xb3,0xb4,0xe3,0x65,0xb6,0xb7, // и й к л м н о п + // a б->ё в г д e ж з // 4 р с т у ф х ц ч + 0xb8,0xb9,0xba,0xbb,0xbc,0xbd,0x6f,0xbe, // ш щ ъ ы ь э ю я + // и й к л м н o п // 5 ѐ ё ђ ѓ є ѕ і ї + 0x70,0x63,0xbf,0x79,0xe4,0x78,0xe5,0xc0, // ј љ њ ћ ќ ѝ ў џ + // p c т y ф x ц ч // 6 Ѡ ѡ Ѣ ѣ Ѥ ѥ Ѧ ѧ + 0xc1,0xe6,0xc2,0xc3,0xc4,0xc5,0xc6,0xc7 // Ѫ ѩ Ѫ ѫ Ѭ ѭ Ѯ ѯ + // ш щ ъ ы ь э ю я // 7 Ѱ ѱ Ѳ ѳ Ѵ ѵ Ѷ ѷ + }; // ѻ ѹ Ѻ ѻ Ѽ ѽ Ѿ ѿ #elif ENABLED(MAPPER_C2C3) #error "Western languages on a CYRILLIC display makes no sense. There are no matching symbols." #elif ENABLED(MAPPER_E382E383) @@ -148,7 +150,7 @@ #if ENABLED(MAPPER_C2C3) - char charset_mapper(char c) { + char charset_mapper(const char c) { static uint8_t utf_hi_char; // UTF-8 high part static bool seen_c2 = false; uint8_t d = c; @@ -179,7 +181,7 @@ #elif ENABLED(MAPPER_CECF) - char charset_mapper(char c) { + char charset_mapper(const char c) { static uint8_t utf_hi_char; // UTF-8 high part static bool seen_ce = false; uint8_t d = c; @@ -210,7 +212,7 @@ #elif ENABLED(MAPPER_CECF) - char charset_mapper(char c) { + char charset_mapper(const char c) { static uint8_t utf_hi_char; // UTF-8 high part static bool seen_ce = false; uint8_t d = c; @@ -241,7 +243,7 @@ #elif ENABLED(MAPPER_D0D1_MOD) - char charset_mapper(char c) { + char charset_mapper(const char c) { // it is a Russian alphabet translation // except 0401 --> 0xa2 = Ё, 0451 --> 0xb5 = ё static uint8_t utf_hi_char; // UTF-8 high part @@ -278,7 +280,7 @@ #elif ENABLED(MAPPER_D0D1) - char charset_mapper(char c) { + char charset_mapper(const char c) { static uint8_t utf_hi_char; // UTF-8 high part static bool seen_d5 = false; uint8_t d = c; @@ -309,7 +311,7 @@ #elif ENABLED(MAPPER_E382E383) - char charset_mapper(char c) { + char charset_mapper(const char c) { static uint8_t utf_hi_char; // UTF-8 high part static bool seen_e3 = false; static bool seen_82_83 = false; @@ -348,7 +350,7 @@ #define MAPPER_NON - char charset_mapper(char c) { + char charset_mapper(const char c) { HARDWARE_CHAR_OUT( c ); return 1; } diff --git a/Marlin/utility.cpp b/Marlin/utility.cpp index 0285219c40..8d638067b0 100644 --- a/Marlin/utility.cpp +++ b/Marlin/utility.cpp @@ -32,3 +32,225 @@ void safe_delay(millis_t ms) { } delay(ms); } + +#if ENABLED(ULTRA_LCD) + + char conv[9]; + + #define DIGIT(n) ('0' + (n)) + #define DIGIMOD(n, f) DIGIT((n)/(f) % 10) + #define RJDIGIT(n, f) ((n) >= (f) ? DIGIMOD(n, f) : ' ') + #define MINUSOR(n, alt) (n >= 0 ? (alt) : (n = -n, '-')) + + // Convert unsigned int to string with 12 format + char* itostr2(const uint8_t& x) { + int xx = x; + conv[0] = DIGIMOD(xx, 10); + conv[1] = DIGIMOD(xx, 1); + conv[2] = '\0'; + return conv; + } + + // Convert signed int to rj string with 123 or -12 format + char* itostr3(const int& x) { + int xx = x; + conv[0] = MINUSOR(xx, RJDIGIT(xx, 100)); + conv[1] = RJDIGIT(xx, 10); + conv[2] = DIGIMOD(xx, 1); + conv[3] = '\0'; + return conv; + } + + // Convert unsigned int to lj string with 123 format + char* itostr3left(const int& xx) { + char *str = &conv[3]; + *str = '\0'; + *(--str) = DIGIMOD(xx, 1); + if (xx >= 10) { + *(--str) = DIGIMOD(xx, 10); + if (xx >= 100) + *(--str) = DIGIMOD(xx, 100); + } + return str; + } + + // Convert signed int to rj string with 1234, _123, -123, _-12, or __-1 format + char *itostr4sign(const int& x) { + int xx = abs(x); + if (x >= 1000) { + conv[0] = DIGIMOD(xx, 1000); + conv[1] = DIGIMOD(xx, 100); + conv[2] = DIGIMOD(xx, 10); + } + else { + if (xx >= 100) { + conv[0] = x < 0 ? '-' : ' '; + conv[1] = DIGIMOD(xx, 100); + conv[2] = DIGIMOD(xx, 10); + } + else { + conv[0] = ' '; + if (xx >= 10) { + conv[1] = x < 0 ? '-' : ' '; + conv[2] = DIGIMOD(xx, 10); + } + else { + conv[1] = ' '; + conv[2] = x < 0 ? '-' : ' '; + } + } + } + conv[3] = DIGIMOD(xx, 1); + conv[4] = '\0'; + return conv; + } + + // Convert unsigned float to string with 1.23 format + char* ftostr12ns(const float& x) { + long xx = abs(x * 100); + conv[0] = DIGIMOD(xx, 100); + conv[1] = '.'; + conv[2] = DIGIMOD(xx, 10); + conv[3] = DIGIMOD(xx, 1); + conv[4] = '\0'; + return conv; + } + + // Convert signed float to fixed-length string with 023.45 / -23.45 format + char *ftostr32(const float& x) { + long xx = x * 100; + conv[0] = MINUSOR(xx, DIGIMOD(xx, 10000)); + conv[1] = DIGIMOD(xx, 1000); + conv[2] = DIGIMOD(xx, 100); + conv[3] = '.'; + conv[4] = DIGIMOD(xx, 10); + conv[5] = DIGIMOD(xx, 1); + conv[6] = '\0'; + return conv; + } + + #if ENABLED(LCD_DECIMAL_SMALL_XY) + + // Convert float to rj string with 1234, _123, -123, _-12, 12.3, _1.2, or -1.2 format + char *ftostr4sign(const float& fx) { + int x = fx * 10; + if (x <= -100 || x >= 1000) return itostr4sign((int)fx); + int xx = abs(x); + conv[0] = x < 0 ? '-' : (xx >= 100 ? DIGIMOD(xx, 100) : ' '); + conv[1] = DIGIMOD(xx, 10); + conv[2] = '.'; + conv[3] = DIGIMOD(xx, 1); + conv[4] = '\0'; + return conv; + } + + #endif // LCD_DECIMAL_SMALL_XY + + // Convert float to fixed-length string with +123.4 / -123.4 format + char* ftostr41sign(const float& x) { + int xx = x * 10; + conv[0] = MINUSOR(xx, '+'); + conv[1] = DIGIMOD(xx, 1000); + conv[2] = DIGIMOD(xx, 100); + conv[3] = DIGIMOD(xx, 10); + conv[4] = '.'; + conv[5] = DIGIMOD(xx, 1); + conv[6] = '\0'; + return conv; + } + + // Convert signed float to string (6 digit) with -1.234 / _0.000 / +1.234 format + char* ftostr43sign(const float& x, char plus/*=' '*/) { + long xx = x * 1000; + conv[0] = xx ? MINUSOR(xx, plus) : ' '; + conv[1] = DIGIMOD(xx, 1000); + conv[2] = '.'; + conv[3] = DIGIMOD(xx, 100); + conv[4] = DIGIMOD(xx, 10); + conv[5] = DIGIMOD(xx, 1); + conv[6] = '\0'; + return conv; + } + + // Convert unsigned float to rj string with 12345 format + char* ftostr5rj(const float& x) { + long xx = abs(x); + conv[0] = RJDIGIT(xx, 10000); + conv[1] = RJDIGIT(xx, 1000); + conv[2] = RJDIGIT(xx, 100); + conv[3] = RJDIGIT(xx, 10); + conv[4] = DIGIMOD(xx, 1); + conv[5] = '\0'; + return conv; + } + + // Convert signed float to string with +1234.5 format + char* ftostr51sign(const float& x) { + long xx = x * 10; + conv[0] = MINUSOR(xx, '+'); + conv[1] = DIGIMOD(xx, 10000); + conv[2] = DIGIMOD(xx, 1000); + conv[3] = DIGIMOD(xx, 100); + conv[4] = DIGIMOD(xx, 10); + conv[5] = '.'; + conv[6] = DIGIMOD(xx, 1); + conv[7] = '\0'; + return conv; + } + + // Convert signed float to string with +123.45 format + char* ftostr52sign(const float& x) { + long xx = x * 100; + conv[0] = MINUSOR(xx, '+'); + conv[1] = DIGIMOD(xx, 10000); + conv[2] = DIGIMOD(xx, 1000); + conv[3] = DIGIMOD(xx, 100); + conv[4] = '.'; + conv[5] = DIGIMOD(xx, 10); + conv[6] = DIGIMOD(xx, 1); + conv[7] = '\0'; + return conv; + } + + // Convert signed float to string with +1234.56 format + char* ftostr62sign(const float& x) { + long xx = abs(x * 100); + conv[0] = MINUSOR(xx, '+'); + conv[1] = DIGIMOD(xx, 100000); + conv[2] = DIGIMOD(xx, 10000); + conv[3] = DIGIMOD(xx, 1000); + conv[4] = DIGIMOD(xx, 100); + conv[5] = '.'; + conv[6] = DIGIMOD(xx, 10); + conv[7] = DIGIMOD(xx, 1); + conv[8] = '\0'; + return conv; + } + + // Convert signed float to space-padded string with -_23.4_ format + char* ftostr52sp(const float& x) { + long xx = x * 100; + uint8_t dig; + conv[0] = MINUSOR(xx, RJDIGIT(xx, 10000)); + conv[1] = RJDIGIT(xx, 1000); + conv[2] = DIGIMOD(xx, 100); + + if ((dig = xx % 10)) { // second digit after decimal point? + conv[3] = '.'; + conv[4] = DIGIMOD(xx, 10); + conv[5] = DIGIT(dig); + } + else { + if ((dig = (xx / 10) % 10)) { // first digit after decimal point? + conv[3] = '.'; + conv[4] = DIGIT(dig); + } + else // nothing after decimal point + conv[3] = conv[4] = ' '; + conv[5] = ' '; + } + conv[6] = '\0'; + return conv; + } + +#endif // ULTRA_LCD diff --git a/Marlin/utility.h b/Marlin/utility.h index 8ca70dbf83..09d569debb 100644 --- a/Marlin/utility.h +++ b/Marlin/utility.h @@ -25,4 +25,58 @@ void safe_delay(millis_t ms); -#endif +#if ENABLED(ULTRA_LCD) + + // Convert unsigned int to string with 12 format + char* itostr2(const uint8_t& x); + + // Convert signed int to rj string with 123 or -12 format + char* itostr3(const int& x); + + // Convert unsigned int to lj string with 123 format + char* itostr3left(const int& xx); + + // Convert signed int to rj string with _123, -123, _-12, or __-1 format + char *itostr4sign(const int& x); + + // Convert unsigned float to string with 1.23 format + char* ftostr12ns(const float& x); + + // Convert signed float to fixed-length string with 023.45 / -23.45 format + char *ftostr32(const float& x); + + // Convert float to fixed-length string with +123.4 / -123.4 format + char* ftostr41sign(const float& x); + + // Convert signed float to string (6 digit) with -1.234 / _0.000 / +1.234 format + char* ftostr43sign(const float& x, char plus=' '); + + // Convert unsigned float to rj string with 12345 format + char* ftostr5rj(const float& x); + + // Convert signed float to string with +1234.5 format + char* ftostr51sign(const float& x); + + // Convert signed float to space-padded string with -_23.4_ format + char* ftostr52sp(const float& x); + + // Convert signed float to string with +123.45 format + char* ftostr52sign(const float& x); + + // Convert signed float to string with +1234.56 format + char* ftostr62sign(const float& x); + + // Convert float to rj string with 123 or -12 format + FORCE_INLINE char *ftostr3(const float& x) { return itostr3((int)x); } + + #if ENABLED(LCD_DECIMAL_SMALL_XY) + // Convert float to rj string with 1234, _123, 12.3, _1.2, -123, _-12, or -1.2 format + char *ftostr4sign(const float& fx); + #else + // Convert float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format + FORCE_INLINE char *ftostr4sign(const float& x) { return itostr4sign((int)x); } + #endif + +#endif // ULTRA_LCD + +#endif // __UTILITY_H__ diff --git a/Marlin/vector_3.cpp b/Marlin/vector_3.cpp index 1cca0d9d8d..c5f0cc0547 100644 --- a/Marlin/vector_3.cpp +++ b/Marlin/vector_3.cpp @@ -41,7 +41,7 @@ #include #include "Marlin.h" -#if ENABLED(AUTO_BED_LEVELING_FEATURE) +#if HAS_ABL #include "vector_3.h" vector_3::vector_3() : x(0), y(0), z(0) { } @@ -156,5 +156,5 @@ void matrix_3x3::debug(const char title[]) { } } -#endif // AUTO_BED_LEVELING_FEATURE +#endif // HAS_ABL diff --git a/Marlin/vector_3.h b/Marlin/vector_3.h index e76188b04b..efc0132fe5 100644 --- a/Marlin/vector_3.h +++ b/Marlin/vector_3.h @@ -41,7 +41,7 @@ #ifndef VECTOR_3_H #define VECTOR_3_H -#if ENABLED(AUTO_BED_LEVELING_FEATURE) +#if HAS_ABL class matrix_3x3; struct vector_3 { @@ -77,6 +77,6 @@ struct matrix_3x3 { void apply_rotation_xyz(matrix_3x3 rotationMatrix, float& x, float& y, float& z); -#endif // AUTO_BED_LEVELING_FEATURE +#endif // HAS_ABL #endif // VECTOR_3_H diff --git a/buildroot/bin/opt_disable_adv b/buildroot/bin/opt_disable_adv old mode 100644 new mode 100755 diff --git a/buildroot/bin/restore_configs b/buildroot/bin/restore_configs index ba7a72cd89..73240bd438 100755 --- a/buildroot/bin/restore_configs +++ b/buildroot/bin/restore_configs @@ -2,7 +2,7 @@ cp Marlin/Configuration.h.backup Marlin/Configuration.h cp Marlin/Configuration_adv.h.backup Marlin/Configuration_adv.h -cp Marlin/pins_RAMPS_14.h.backup Marlin/pins_RAMPS_14.h +cp Marlin/pins_RAMPS.h.backup Marlin/pins_RAMPS.h if [ -f Marlin/_Bootscreen.h ]; then rm Marlin/_Bootscreen.h diff --git a/buildroot/share/cmake/CMakeLists.txt b/buildroot/share/cmake/CMakeLists.txt new file mode 100644 index 0000000000..334afaa904 --- /dev/null +++ b/buildroot/share/cmake/CMakeLists.txt @@ -0,0 +1,128 @@ +cmake_minimum_required(VERSION 2.8) +#====================================================================# +# Usage under Linux: # +# # +# From Marlin/buildroot/share/cmake folder: # +# mkdir -p build && cd build # +# cmake .. # +# make # +# # +# Usage under Windows: # +# # +# From Marlin/buildroot/share/cmake folder: : # +# mkdir build && cd build # +# cmake -G"Unix Makefiles" .. # +# make # +#====================================================================# + +#====================================================================# +# Download marlin-cmake scriptfiles if not already installed # +# and add the path to the module path # +#====================================================================# + +if(NOT EXISTS ${CMAKE_BINARY_DIR}/marlin-cmake) + + file(DOWNLOAD https://raw.githubusercontent.com/tohara/marlin-cmake/v1.0.0/modules/Arduino_SDK.cmake + ${CMAKE_BINARY_DIR}/marlin-cmake/modules/Arduino_SDK.cmake SHOW_PROGRESS) + + file(DOWNLOAD https://raw.githubusercontent.com/tohara/marlin-cmake/v1.0.0/modules/marlin_cmake_functions.cmake + ${CMAKE_BINARY_DIR}/marlin-cmake/modules/marlin_cmake_functions.cmake SHOW_PROGRESS) + + file(DOWNLOAD https://raw.githubusercontent.com/tohara/marlin-cmake/v1.0.0/Platform/Arduino.cmake + ${CMAKE_BINARY_DIR}/marlin-cmake/Platform/Arduino.cmake SHOW_PROGRESS) + + file(DOWNLOAD https://raw.githubusercontent.com/tohara/marlin-cmake/v1.0.0/settings/marlin_boards.txt + ${CMAKE_BINARY_DIR}/marlin-cmake/settings/marlin_boards.txt SHOW_PROGRESS) + + file(DOWNLOAD https://raw.githubusercontent.com/tohara/marlin-cmake/v1.0.0/toolchain/ArduinoToolchain.cmake + ${CMAKE_BINARY_DIR}/marlin-cmake/toolchain/ArduinoToolchain.cmake SHOW_PROGRESS) + + if(WIN32) + file(DOWNLOAD https://raw.githubusercontent.com/tohara/marlin-cmake/v1.0.0/resources/make.exe + ${CMAKE_BINARY_DIR}/make.exe SHOW_PROGRESS) + endif(WIN32) + +endif() + +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${CMAKE_BINARY_DIR}/marlin-cmake/modules) + +#====================================================================# +# Custom path to Arduino SDK can be set here. # +# It can also be set from command line. eg.: # +# cmake .. -DARDUINO_SDK_PATH="/path/to/arduino-1.x.x" # +#====================================================================# +#set(ARDUINO_SDK_PATH ${CMAKE_CURRENT_LIST_DIR}/arduino-1.6.8) +#set(ARDUINO_SDK_PATH /home/tom/git/BigBox-Dual-Marlin/ArduinoAddons/Arduino_1.6.x) +#set(ARDUINO_SDK_PATH /home/tom/test/arduino-1.6.11) +#====================================================================# +# Set included cmake files # +#====================================================================# +include(Arduino_SDK) # Find the intallpath of Arduino SDK +include(marlin_cmake_functions) + +#====================================================================# +# Set toolchain file for arduino # +#====================================================================# +set(CMAKE_TOOLCHAIN_FILE ${CMAKE_BINARY_DIR}/marlin-cmake/toolchain/ArduinoToolchain.cmake) # Arduino Toolchain + +#====================================================================# +# Setup Project # +#====================================================================# +project(Marlin C CXX) + +#====================================================================# +# Register non standard hardware # +#====================================================================# +#register_hardware_platform(/home/tom/test/Sanguino) + +#====================================================================# +# Print any info # +# print_board_list() # +# print_programmer_list() # +# print_board_settings(mega) # +#====================================================================# +print_board_list() +print_programmer_list() + + +#====================================================================# +# Get motherboard settings from Configuration.h # +# setup_motherboard(TARGET Marlin_src_folder) # +# Returns ${TARGET}_BOARD and ${TARGET}_CPU # +# # +# To set it manually: # +# set(${PROJECT_NAME}_BOARD mega) # +# set(${PROJECT_NAME}_CPU atmega2560) # +#====================================================================# +setup_motherboard(${PROJECT_NAME} ${CMAKE_CURRENT_LIST_DIR}/../../../Marlin) + +#====================================================================# +# Setup all source files # +# Incude Marlin.ino to compile libs not included in *.cpp files # +#====================================================================# + +file(GLOB SOURCES "../../../Marlin/*.cpp") +set(${PROJECT_NAME}_SRCS "${SOURCES};../../../Marlin/Marlin.ino") + +#====================================================================# +# Define the port for uploading code to the Arduino # +# Can be set from commandline with: # +# cmake .. -DUPLOAD_PORT=/dev/ttyACM0 # +#====================================================================# +if(UPLOAD_PORT) + set(${PROJECT_NAME}_PORT ${UPLOAD_PORT}) +else() + set(${PROJECT_NAME}_PORT /dev/ttyACM0) +endif() + +#====================================================================# +# Register arduino libraries not included in SDK # +#====================================================================# +#link_directories(/home/tom/test/ArduinoAddons) #U8glib +#set(${PROJECT_NAME}_ARDLIBS U8glib) +#set(U8glib_RECURSE True) + +#====================================================================# +# Command to generate code arduino firmware (.hex file) # +#====================================================================# +generate_arduino_firmware(${PROJECT_NAME}) diff --git a/buildroot/share/fonts/ISO10646-1-tr.fon b/buildroot/share/fonts/ISO10646-1-tr.fon new file mode 100644 index 0000000000..f6f6cdec7e Binary files /dev/null and b/buildroot/share/fonts/ISO10646-1-tr.fon differ diff --git a/buildroot/share/fonts/ISO10646-4_Greek.fon b/buildroot/share/fonts/ISO10646-4_Greek.fon index 021078e00b..a6b905fefb 100644 Binary files a/buildroot/share/fonts/ISO10646-4_Greek.fon and b/buildroot/share/fonts/ISO10646-4_Greek.fon differ diff --git a/buildroot/share/fonts/make_fonts.bat b/buildroot/share/fonts/make_fonts.bat index c4df633e44..fffd90a669 100644 --- a/buildroot/share/fonts/make_fonts.bat +++ b/buildroot/share/fonts/make_fonts.bat @@ -3,6 +3,7 @@ .\bdf2u8g.exe -b 32 -e 255 HD44780_C.bdf HD44780_C_5x7 dogm_font_data_HD44780_C.h .\bdf2u8g.exe -b 32 -e 255 HD44780_J.bdf HD44780_J_5x7 dogm_font_data_HD44780_J.h .\bdf2u8g.exe -b 32 -e 255 ISO10646-1.bdf ISO10646_1_5x7 dogm_font_data_ISO10646_1.h +.\bdf2u8g.exe -b 32 -e 255 ISO10646-1-tr.bdf ISO10646_1_tr_5x7 dogm_font_data_ISO10646_1-tr.h .\bdf2u8g.exe -b 32 -e 255 ISO10646_5_Cyrillic.bdf ISO10646_5_Cyrillic_5x7 dogm_font_data_ISO10646_5_Cyrillic.h .\bdf2u8g.exe -b 32 -e 255 ISO10646_Kana.bdf ISO10646_Kana_5x7 dogm_font_data_ISO10646_Kana.h .\bdf2u8g.exe -b 32 -e 255 ISO10646_CN.bdf ISO10646_CN dogm_font_data_ISO10646_CN.h diff --git a/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino b/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino new file mode 100644 index 0000000000..8650a3d132 --- /dev/null +++ b/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino @@ -0,0 +1,32 @@ +// Search pins uasable for endstop-interupts +// Compile with the same settings you'd use with Marlin. + +#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) ) +#endif + +void setup() { + Serial.begin(9600); + Serial.println("PINs causing interrups are:"); + for(int i=2; i